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 boost::shared_ptr < const BoundaryEstimation < PointInT, PointNT, PointOutT > > | ConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < BoundaryEstimation< PointInT, PointNT, PointOutT > > | Ptr |
Public Member Functions | |
BoundaryEstimation () | |
Empty constructor. The angular threshold angle_threshold_ is set to M_PI / 2.0. | |
float | getAngleThreshold () |
Get the decision boundary (angle threshold) as set by the user. | |
void | getCoordinateSystemOnPlane (const PointNT &p_coeff, Eigen::Vector4f &u, Eigen::Vector4f &v) |
Get a u-v-n coordinate system that lies on a plane defined by its normal. | |
bool | isBoundaryPoint (const pcl::PointCloud< PointInT > &cloud, int q_idx, const std::vector< int > &indices, const Eigen::Vector4f &u, const Eigen::Vector4f &v, const 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, const PointInT &q_point, const std::vector< int > &indices, const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold) |
Check whether a point is a boundary point in a planar patch of projected points given by indices. | |
void | setAngleThreshold (float angle) |
Set 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 () | |
Protected Attributes | |
float | angle_threshold_ |
The decision boundary (angle threshold) that marks points as boundary or regular. (default ) |
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.
Here's an example for estimating boundary points for a PointXYZ point cloud:
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); // fill in the cloud data here pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>); // estimate normals and fill in \a normals pcl::PointCloud<pcl::Boundary> boundaries; pcl::BoundaryEstimation<pcl::PointXYZ, pcl::Normal, pcl::Boundary> est; est.setInputCloud (cloud); est.setInputNormals (normals); est.setRadiusSearch (0.02); // 2cm radius est.setSearchMethod (typename pcl::search::KdTree<PointXYZ>::Ptr (new pcl::search::KdTree<PointXYZ>) est.compute (boundaries);
Definition at line 81 of file boundary.h.
typedef boost::shared_ptr<const BoundaryEstimation<PointInT, PointNT, PointOutT> > pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::ConstPtr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 85 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 98 of file boundary.h.
typedef boost::shared_ptr<BoundaryEstimation<PointInT, PointNT, PointOutT> > pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::Ptr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 84 of file boundary.h.
pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::BoundaryEstimation | ( | ) | [inline] |
Empty constructor. The angular threshold angle_threshold_ is set to M_PI / 2.0.
Definition at line 104 of file boundary.h.
void pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [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 ()
[out] | output | the resultant point cloud model dataset that contains boundary point estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 117 of file boundary.hpp.
float pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::getAngleThreshold | ( | ) | [inline] |
Get the decision boundary (angle threshold) as set by the user.
Definition at line 150 of file boundary.h.
void pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::getCoordinateSystemOnPlane | ( | const PointNT & | p_coeff, |
Eigen::Vector4f & | u, | ||
Eigen::Vector4f & | v | ||
) | [inline] |
Get a u-v-n coordinate system that lies on a plane defined by its normal.
[in] | p_coeff | the plane coefficients (containing the plane normal) |
[out] | u | the resultant u direction |
[out] | v | the resultant v direction |
Definition at line 161 of file boundary.h.
bool pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint | ( | const pcl::PointCloud< PointInT > & | cloud, |
int | q_idx, | ||
const std::vector< int > & | indices, | ||
const Eigen::Vector4f & | u, | ||
const Eigen::Vector4f & | v, | ||
const float | angle_threshold | ||
) |
Check whether a point is a boundary point in a planar patch of projected points given by indices.
[in] | cloud | a pointer to the input point cloud |
[in] | q_idx | the index of the query point in cloud |
[in] | indices | the estimated point neighbors of the query point |
[in] | u | the u direction |
[in] | v | the v direction |
[in] | angle_threshold | the threshold angle (default ) |
Definition at line 49 of file boundary.hpp.
bool pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint | ( | const pcl::PointCloud< PointInT > & | cloud, |
const PointInT & | q_point, | ||
const std::vector< int > & | indices, | ||
const Eigen::Vector4f & | u, | ||
const Eigen::Vector4f & | v, | ||
const float | angle_threshold | ||
) |
Check whether a point is a boundary point in a planar patch of projected points given by indices.
[in] | cloud | a pointer to the input point cloud |
[in] | q_point | a pointer to the querry point |
[in] | indices | the estimated point neighbors of the query point |
[in] | u | the u direction |
[in] | v | the v direction |
[in] | angle_threshold | the threshold angle (default ) |
Definition at line 60 of file boundary.hpp.
void pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::setAngleThreshold | ( | float | angle | ) | [inline] |
Set the decision boundary (angle threshold) that marks points as boundary or regular. (default )
[in] | angle | the angle threshold |
Definition at line 143 of file boundary.h.
float pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::angle_threshold_ [protected] |
The decision boundary (angle threshold) that marks points as boundary or regular. (default )
Definition at line 179 of file boundary.h.