40 class PinholeCameraIntrinsic;
59 bool IsEmpty()
const override;
60 Eigen::Vector3d GetMinBound()
const override;
61 Eigen::Vector3d GetMaxBound()
const override;
62 Eigen::Vector3d GetCenter()
const override;
65 PointCloud &Transform(
const Eigen::Matrix4d &transformation)
override;
66 PointCloud &Translate(
const Eigen::Vector3d &translation,
67 bool relative =
true)
override;
68 PointCloud &Scale(
const double scale,
bool center =
true)
override;
69 PointCloud &Rotate(
const Eigen::Matrix3d &R,
bool center =
true)
override;
74 bool HasPoints()
const {
return points_.size() > 0; }
77 return points_.size() > 0 && normals_.size() == points_.size();
81 return points_.size() > 0 && colors_.size() == points_.size();
85 for (
size_t i = 0; i < normals_.size(); i++) {
86 normals_[i].normalize();
93 ResizeAndPaintUniformColor(colors_, points_.size(), color);
100 PointCloud &RemoveNoneFinitePoints(
bool remove_nan =
true,
101 bool remove_infinite =
true);
106 std::shared_ptr<PointCloud> SelectDownSample(
107 const std::vector<size_t> &indices,
bool invert =
false)
const;
113 std::shared_ptr<PointCloud> VoxelDownSample(
double voxel_size)
const;
117 std::tuple<std::shared_ptr<PointCloud>, Eigen::MatrixXi>
118 VoxelDownSampleAndTrace(
double voxel_size,
119 const Eigen::Vector3d &min_bound,
120 const Eigen::Vector3d &max_bound,
121 bool approximate_class =
false)
const;
125 std::shared_ptr<PointCloud> UniformDownSample(
size_t every_k_points)
const;
139 std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
140 RemoveRadiusOutliers(
size_t nb_points,
double search_radius)
const;
144 std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
145 RemoveStatisticalOutliers(
size_t nb_neighbors,
double std_ratio)
const;
152 bool EstimateNormals(
154 bool fast_normal_computation =
true);
159 bool OrientNormalsToAlignWithDirection(
160 const Eigen::Vector3d &orientation_reference =
161 Eigen::Vector3d(0.0, 0.0, 1.0));
166 bool OrientNormalsTowardsCameraLocation(
167 const Eigen::Vector3d &camera_location = Eigen::Vector3d::Zero());
174 std::vector<double> ComputePointCloudDistance(
const PointCloud &target);
178 std::tuple<Eigen::Vector3d, Eigen::Matrix3d> ComputeMeanAndCovariance()
184 std::vector<double> ComputeMahalanobisDistance()
const;
188 std::vector<double> ComputeNearestNeighborDistance()
const;
191 std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
192 ComputeConvexHull()
const;
201 std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
202 HiddenPointRemoval(
const Eigen::Vector3d &camera_location,
203 const double radius)
const;
210 std::vector<int> ClusterDBSCAN(
double eps,
212 bool print_progress =
false)
const;
223 std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
224 const double distance_threshold = 0.01,
225 const int ransac_n = 3,
226 const int num_iterations = 100)
const;
235 static std::shared_ptr<PointCloud> CreateFromDepthImage(
238 const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
239 double depth_scale = 1000.0,
240 double depth_trunc = 1000.0,
246 static std::shared_ptr<PointCloud> CreateFromRGBDImage(
249 const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity());
254 std::shared_ptr<PointCloud> CreateFromVoxelGrid(
The base geometry class.
Definition: Geometry.h:35
A bounding box that is aligned along the coordinate axes.
Definition: BoundingVolume.h:130
Contains the pinhole camera intrinsic parameters.
Definition: PinholeCameraIntrinsic.h:51
A bounding box oriented along an arbitrary frame of reference.
Definition: BoundingVolume.h:44
Definition: PointCloud.h:50
bool HasPoints() const
Definition: PointCloud.h:74
PointCloud & NormalizeNormals()
Definition: PointCloud.h:84
std::vector< Eigen::Vector3d > points_
Definition: PointCloud.h:258
PointCloud()
Definition: PointCloud.h:52
double voxel_size
Definition: FilePLY.cpp:285
PointCloud & PaintUniformColor(const Eigen::Vector3d &color)
Assigns each point in the PointCloud the same color.
Definition: PointCloud.h:92
std::vector< Eigen::Vector3d > colors_
Definition: PointCloud.h:260
The base geometry class for 3D geometries.
Definition: Geometry3D.h:46
Definition: KDTreeSearchParam.h:32
Definition: RGBDImage.h:43
std::vector< Eigen::Vector3d > normals_
Definition: PointCloud.h:259
bool HasNormals() const
Definition: PointCloud.h:76
int points
Definition: FilePCD.cpp:70
Definition: PinholeCameraIntrinsic.cpp:34
~PointCloud() override
Definition: PointCloud.h:55
Definition: VoxelGrid.h:65
GeometryType
Specifies possible geometry types.
Definition: Geometry.h:40
bool HasColors() const
Definition: PointCloud.h:80
Definition: KDTreeSearchParam.h:53
PointCloud(const std::vector< Eigen::Vector3d > &points)
Definition: PointCloud.h:53
The Image class stores image with customizable width, height, num of channels and bytes per channel...
Definition: Image.h:53