Loading [MathJax]/extensions/TeX/AMSsymbols.js
Open3D (C++ API)  0.14.1
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
PointCloud.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // The MIT License (MIT)
5 //
6 // Copyright (c) 2018-2021 www.open3d.org
7 //
8 // Permission is hereby granted, free of charge, to any person obtaining a copy
9 // of this software and associated documentation files (the "Software"), to deal
10 // in the Software without restriction, including without limitation the rights
11 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12 // copies of the Software, and to permit persons to whom the Software is
13 // furnished to do so, subject to the following conditions:
14 //
15 // The above copyright notice and this permission notice shall be included in
16 // all copies or substantial portions of the Software.
17 //
18 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
23 // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
24 // IN THE SOFTWARE.
25 // ----------------------------------------------------------------------------
26 
27 #pragma once
28 
29 #include <Eigen/Core>
30 #include <memory>
31 #include <tuple>
32 #include <vector>
33 
37 
38 namespace open3d {
39 
40 namespace camera {
41 class PinholeCameraIntrinsic;
42 }
43 
44 namespace geometry {
45 
46 class Image;
47 class RGBDImage;
48 class TriangleMesh;
49 class VoxelGrid;
50 
55 class PointCloud : public Geometry3D {
56 public:
62  PointCloud(const std::vector<Eigen::Vector3d> &points)
63  : Geometry3D(Geometry::GeometryType::PointCloud), points_(points) {}
64  ~PointCloud() override {}
65 
66 public:
67  PointCloud &Clear() override;
68  bool IsEmpty() const override;
69  Eigen::Vector3d GetMinBound() const override;
70  Eigen::Vector3d GetMaxBound() const override;
71  Eigen::Vector3d GetCenter() const override;
72  AxisAlignedBoundingBox GetAxisAlignedBoundingBox() const override;
73  OrientedBoundingBox GetOrientedBoundingBox() const override;
74  PointCloud &Transform(const Eigen::Matrix4d &transformation) override;
75  PointCloud &Translate(const Eigen::Vector3d &translation,
76  bool relative = true) override;
77  PointCloud &Scale(const double scale,
78  const Eigen::Vector3d &center) override;
79  PointCloud &Rotate(const Eigen::Matrix3d &R,
80  const Eigen::Vector3d &center) override;
81 
82  PointCloud &operator+=(const PointCloud &cloud);
83  PointCloud operator+(const PointCloud &cloud) const;
84 
86  bool HasPoints() const { return points_.size() > 0; }
87 
89  bool HasNormals() const {
90  return points_.size() > 0 && normals_.size() == points_.size();
91  }
92 
94  bool HasColors() const {
95  return points_.size() > 0 && colors_.size() == points_.size();
96  }
97 
99  bool HasCovariances() const {
100  return !points_.empty() && covariances_.size() == points_.size();
101  }
102 
105  for (size_t i = 0; i < normals_.size(); i++) {
106  normals_[i].normalize();
107  }
108  return *this;
109  }
110 
114  PointCloud &PaintUniformColor(const Eigen::Vector3d &color) {
115  ResizeAndPaintUniformColor(colors_, points_.size(), color);
116  return *this;
117  }
118 
126  PointCloud &RemoveNonFinitePoints(bool remove_nan = true,
127  bool remove_infinite = true);
128 
136  std::shared_ptr<PointCloud> SelectByIndex(
137  const std::vector<size_t> &indices, bool invert = false) const;
138 
146  std::shared_ptr<PointCloud> VoxelDownSample(double voxel_size) const;
147 
156  std::tuple<std::shared_ptr<PointCloud>,
157  Eigen::MatrixXi,
158  std::vector<std::vector<int>>>
159  VoxelDownSampleAndTrace(double voxel_size,
160  const Eigen::Vector3d &min_bound,
161  const Eigen::Vector3d &max_bound,
162  bool approximate_class = false) const;
163 
172  std::shared_ptr<PointCloud> UniformDownSample(size_t every_k_points) const;
173 
182  std::shared_ptr<PointCloud> RandomDownSample(double sampling_ratio) const;
189  std::shared_ptr<PointCloud> Crop(const AxisAlignedBoundingBox &bbox) const;
190 
197  std::shared_ptr<PointCloud> Crop(const OrientedBoundingBox &bbox) const;
198 
205  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
206  RemoveRadiusOutliers(size_t nb_points,
207  double search_radius,
208  bool print_progress = false) const;
209 
215  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
216  RemoveStatisticalOutliers(size_t nb_neighbors,
217  double std_ratio,
218  bool print_progress = false) const;
219 
230  void EstimateNormals(
231  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN(),
232  bool fast_normal_computation = true);
233 
238  void OrientNormalsToAlignWithDirection(
239  const Eigen::Vector3d &orientation_reference =
240  Eigen::Vector3d(0.0, 0.0, 1.0));
241 
246  void OrientNormalsTowardsCameraLocation(
247  const Eigen::Vector3d &camera_location = Eigen::Vector3d::Zero());
248 
255  void OrientNormalsConsistentTangentPlane(size_t k);
256 
264  std::vector<double> ComputePointCloudDistance(const PointCloud &target);
265 
273  static std::vector<Eigen::Matrix3d> EstimatePerPointCovariances(
274  const PointCloud &input,
275  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
276 
283  void EstimateCovariances(
284  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
285 
288  std::tuple<Eigen::Vector3d, Eigen::Matrix3d> ComputeMeanAndCovariance()
289  const;
290 
295  std::vector<double> ComputeMahalanobisDistance() const;
296 
299  std::vector<double> ComputeNearestNeighborDistance() const;
300 
302  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
303  ComputeConvexHull() const;
304 
314  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
315  HiddenPointRemoval(const Eigen::Vector3d &camera_location,
316  const double radius) const;
317 
329  std::vector<int> ClusterDBSCAN(double eps,
330  size_t min_points,
331  bool print_progress = false) const;
332 
345  std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
346  const double distance_threshold = 0.01,
347  const int ransac_n = 3,
348  const int num_iterations = 100,
350 
370  static std::shared_ptr<PointCloud> CreateFromDepthImage(
371  const Image &depth,
372  const camera::PinholeCameraIntrinsic &intrinsic,
373  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
374  double depth_scale = 1000.0,
375  double depth_trunc = 1000.0,
376  int stride = 1,
377  bool project_valid_depth_only = true);
378 
395  static std::shared_ptr<PointCloud> CreateFromRGBDImage(
396  const RGBDImage &image,
397  const camera::PinholeCameraIntrinsic &intrinsic,
398  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
399  bool project_valid_depth_only = true);
400 
407  std::shared_ptr<PointCloud> CreateFromVoxelGrid(
408  const VoxelGrid &voxel_grid);
409 
410 public:
412  std::vector<Eigen::Vector3d> points_;
414  std::vector<Eigen::Vector3d> normals_;
416  std::vector<Eigen::Vector3d> colors_;
418  std::vector<Eigen::Matrix3d> covariances_;
419 };
420 
421 } // namespace geometry
422 } // namespace open3d
constexpr nullopt_t nullopt
Definition: Optional.h:171
std::tuple< Eigen::Vector3d, Eigen::Matrix3d > ComputeMeanAndCovariance(const std::vector< Eigen::Vector3d > &points, const std::vector< IdxType > &indices)
Function to compute the mean and covariance matrix of a set of points.
Definition: Eigen.cpp:339
The base geometry class.
Definition: Geometry.h:37
bool HasCovariances() const
Returns &#39;true&#39; if the point cloud contains per-point covariance matrix.
Definition: PointCloud.h:99
A bounding box that is aligned along the coordinate axes.
Definition: BoundingVolume.h:150
Contains the pinhole camera intrinsic parameters.
Definition: PinholeCameraIntrinsic.h:51
A bounding box oriented along an arbitrary frame of reference.
Definition: BoundingVolume.h:44
A point cloud consists of point coordinates, and optionally point colors and point normals...
Definition: PointCloud.h:55
bool HasPoints() const
Returns &#39;true&#39; if the point cloud contains points.
Definition: PointCloud.h:86
int points
Definition: FilePCD.cpp:73
PointCloud & NormalizeNormals()
Normalize point normals to length 1.
Definition: PointCloud.h:104
std::vector< Eigen::Vector3d > points_
Points coordinates.
Definition: PointCloud.h:412
PointCloud()
Default Constructor.
Definition: PointCloud.h:58
math::float4 color
Definition: LineSetBuffers.cpp:64
PointCloud & PaintUniformColor(const Eigen::Vector3d &color)
Definition: PointCloud.h:114
std::vector< Eigen::Vector3d > colors_
RGB colors of points.
Definition: PointCloud.h:416
The base geometry class for 3D geometries.
Definition: Geometry3D.h:47
std::vector< Eigen::Matrix3d > covariances_
Covariance Matrix for each point.
Definition: PointCloud.h:418
Base class for KDTree search parameters.
Definition: KDTreeSearchParam.h:35
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:46
size_t stride
Definition: TriangleMeshBuffers.cpp:184
Definition: Optional.h:79
std::vector< Eigen::Vector3d > normals_
Points normals.
Definition: PointCloud.h:414
bool HasNormals() const
Returns true if the point cloud contains point normals.
Definition: PointCloud.h:89
Definition: PinholeCameraIntrinsic.cpp:35
~PointCloud() override
Definition: PointCloud.h:64
VoxelGrid is a collection of voxels which are aligned in grid.
Definition: VoxelGrid.h:80
GeometryType
Specifies possible geometry types.
Definition: Geometry.h:42
Tensor operator+(T scalar_lhs, const Tensor &rhs)
Definition: Tensor.h:1340
bool HasColors() const
Returns true if the point cloud contains point colors.
Definition: PointCloud.h:94
KDTree search parameters for pure KNN search.
Definition: KDTreeSearchParam.h:63
PointCloud(const std::vector< Eigen::Vector3d > &points)
Parameterized Constructor.
Definition: PointCloud.h:62
The Image class stores image with customizable width, height, num of channels and bytes per channel...
Definition: Image.h:53
std::shared_ptr< core::Tensor > image
Definition: FilamentRenderer.cpp:228