Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
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 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 $\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 ()

Protected Attributes

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

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.

Here's an example for estimating boundary points for a PointXYZ point cloud:

Attention:
The convention for Boundary features is:
  • if a query point's nearest neighbors cannot be estimated, the boundary feature will be set to NaN (not a number)
  • it is impossible to estimate a boundary property for a point that doesn't have finite 3D coordinates. Therefore, any point that contains NaN data on x, y, or z, will have its boundary feature property set to NaN.
Author:
Radu B. Rusu

Definition at line 81 of file boundary.h.


Member Typedef Documentation

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

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 98 of file boundary.h.

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


Constructor & Destructor Documentation

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


Member Function Documentation

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

Parameters:
[out]outputthe resultant point cloud model dataset that contains boundary point estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 117 of file boundary.hpp.

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

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

Parameters:
[in]p_coeffthe plane coefficients (containing the plane normal)
[out]uthe resultant u direction
[out]vthe resultant v direction

Definition at line 161 of file boundary.h.

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

Note:
A coordinate system u-v-n must be computed a-priori using getCoordinateSystemOnPlane
Parameters:
[in]clouda pointer to the input point cloud
[in]q_idxthe index of the query point in cloud
[in]indicesthe estimated point neighbors of the query point
[in]uthe u direction
[in]vthe v direction
[in]angle_thresholdthe threshold angle (default $\pi / 2.0$)

Definition at line 49 of file boundary.hpp.

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

Note:
A coordinate system u-v-n must be computed a-priori using getCoordinateSystemOnPlane
Parameters:
[in]clouda pointer to the input point cloud
[in]q_pointa pointer to the querry point
[in]indicesthe estimated point neighbors of the query point
[in]uthe u direction
[in]vthe v direction
[in]angle_thresholdthe threshold angle (default $\pi / 2.0$)

Definition at line 60 of file boundary.hpp.

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

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

Parameters:
[in]anglethe angle threshold

Definition at line 143 of file boundary.h.


Member Data Documentation

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

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

Definition at line 179 of file boundary.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:39:06