BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset. More...
#include <boundary.h>
Public Types | |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
BoundaryEstimation () | |
Empty constructor. | |
void | getCoordinateSystemOnPlane (const PointNT &p_coeff, Eigen::Vector3f &u, Eigen::Vector3f &v) |
Get a u-v-n coordinate system that lies on a plane defined by its normal. | |
bool | isBoundaryPoint (const pcl::PointCloud< PointInT > &cloud, const PointInT &q_point, const std::vector< int > &indices, const Eigen::Vector3f &u, const Eigen::Vector3f &v, float angle_threshold) |
Check whether a point is a boundary point in a planar patch of projected points given by indices. | |
bool | isBoundaryPoint (const pcl::PointCloud< PointInT > &cloud, int q_idx, const std::vector< int > &indices, const Eigen::Vector3f &u, const Eigen::Vector3f &v, float angle_threshold) |
Check whether a point is a boundary point in a planar patch of projected points given by indices. | |
Public Attributes | |
float | angle_threshold_ |
The decision boundary (angle threshold) that marks points as boundary or regular. (default ). | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate whether a set of points is lying on surface boundaries using an angle criterion for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod (). |
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset.
Definition at line 64 of file boundary.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 76 of file boundary.h.
pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::BoundaryEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 80 of file boundary.h.
void pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [inline, protected, virtual] |
Estimate whether a set of points is lying on surface boundaries using an angle criterion for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().
output | the resultant point cloud model dataset that contains boundary point estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 108 of file boundary.hpp.
void pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::getCoordinateSystemOnPlane | ( | const PointNT & | p_coeff, | |
Eigen::Vector3f & | u, | |||
Eigen::Vector3f & | v | |||
) | [inline] |
Get a u-v-n coordinate system that lies on a plane defined by its normal.
p_coeff | the plane coefficients (containing the plane normal) | |
u | the resultant u direction | |
v | the resultant v direction |
Definition at line 91 of file boundary.h.
bool pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint | ( | const pcl::PointCloud< PointInT > & | cloud, | |
const PointInT & | q_point, | |||
const std::vector< int > & | indices, | |||
const Eigen::Vector3f & | u, | |||
const Eigen::Vector3f & | v, | |||
float | angle_threshold | |||
) | [inline] |
Check whether a point is a boundary point in a planar patch of projected points given by indices.
cloud | a pointer to the input point cloud | |
q_point | a pointer to the querry point | |
indices | the estimated point neighbors of the query point | |
u | the u direction | |
v | the v direction | |
angle_threshold | the threshold angle (default ) |
Definition at line 57 of file boundary.hpp.
bool pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint | ( | const pcl::PointCloud< PointInT > & | cloud, | |
int | q_idx, | |||
const std::vector< int > & | indices, | |||
const Eigen::Vector3f & | u, | |||
const Eigen::Vector3f & | v, | |||
float | angle_threshold | |||
) | [inline] |
Check whether a point is a boundary point in a planar patch of projected points given by indices.
cloud | a pointer to the input point cloud | |
q_idx | the index of the query point in cloud | |
indices | the estimated point neighbors of the query point | |
u | the u direction | |
v | the v direction | |
angle_threshold | the threshold angle (default ) |
Definition at line 46 of file boundary.hpp.
float pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::angle_threshold_ |
The decision boundary (angle threshold) that marks points as boundary or regular. (default ).
Definition at line 122 of file boundary.h.