pcl::BoundaryEstimation< PointInT, PointNT, PointOutT > Class Template Reference

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>

Inheritance diagram for pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

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 $\pi / 2.0$).

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 ().

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT>
class pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >

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.

Note:
The code is stateful as we do not expect this class to be multicore parallelized. Please look at NormalEstimationOpenMP and NormalEstimationTBB for examples on how to extend this to parallel implementations.
Author:
Radu Bogdan Rusu

Definition at line 64 of file boundary.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
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.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::BoundaryEstimation (  )  [inline]

Empty constructor.

Definition at line 80 of file boundary.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
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 ().

Parameters:
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.

template<typename PointInT, typename PointNT, typename PointOutT>
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.

Parameters:
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.

template<typename PointInT , typename PointNT , typename PointOutT >
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.

Note:
A coordinate system u-v-n must be computed a-priori using getCoordinateSystemOnPlane
Parameters:
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 $\pi / 2.0$)

Definition at line 57 of file boundary.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
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.

Note:
A coordinate system u-v-n must be computed a-priori using getCoordinateSystemOnPlane
Parameters:
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 $\pi / 2.0$)

Definition at line 46 of file boundary.hpp.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
float pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::angle_threshold_

The decision boundary (angle threshold) that marks points as boundary or regular. (default $\pi / 2.0$).

Definition at line 122 of file boundary.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:16 2013