#include <fast_edge_estimation_3d.h>

| Public Types | |
| typedef pcl::PointCloud< PointInT > | PointCloudIn | 
| typedef PointCloudIn::ConstPtr | PointCloudInConstPtr | 
| typedef PointCloudIn::Ptr | PointCloudInPtr | 
| typedef pcl::PointCloud< PointNT > | PointCloudN | 
| typedef PointCloudN::ConstPtr | PointCloudNConstPtr | 
| typedef PointCloudN::Ptr | PointCloudNPtr | 
| typedef pcl::PointCloud < PointOutT > | PointCloudOut | 
| Public Member Functions | |
| FastEdgeEstimation3D () | |
| Empty constructor. | |
| void | isEdgePoint (const pcl::PointCloud< PointInT > &cloud, const PointInT &q_point, const std::vector< int > &indices, const Eigen::Vector3f &n, float &strength) | 
| void | setInputNormals (PointCloudNConstPtr cloud) | 
| Protected Member Functions | |
| void | computeFeature (PointCloudOut &output) | 
| Protected Attributes | |
| PointCloudNConstPtr | normals_ | 
Definition at line 71 of file fast_edge_estimation_3d.h.
| typedef pcl::PointCloud<PointInT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudIn | 
Reimplemented from cob_3d_features::OrganizedFeatures< PointInT, PointOutT >.
Definition at line 82 of file fast_edge_estimation_3d.h.
| typedef PointCloudIn::ConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudInConstPtr | 
Reimplemented from cob_3d_features::OrganizedFeatures< PointInT, PointOutT >.
Definition at line 84 of file fast_edge_estimation_3d.h.
| typedef PointCloudIn::Ptr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudInPtr | 
Reimplemented from cob_3d_features::OrganizedFeatures< PointInT, PointOutT >.
Definition at line 83 of file fast_edge_estimation_3d.h.
| typedef pcl::PointCloud<PointNT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudN | 
Definition at line 86 of file fast_edge_estimation_3d.h.
| typedef PointCloudN::ConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudNConstPtr | 
Definition at line 88 of file fast_edge_estimation_3d.h.
| typedef PointCloudN::Ptr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudNPtr | 
Definition at line 87 of file fast_edge_estimation_3d.h.
| typedef pcl::PointCloud<PointOutT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudOut | 
Reimplemented from cob_3d_features::OrganizedFeatures< PointInT, PointOutT >.
Reimplemented in cob_3d_features::FastEdgeEstimation3DOMP< PointInT, PointNT, PointOutT >.
Definition at line 90 of file fast_edge_estimation_3d.h.
| cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::FastEdgeEstimation3D | ( | ) |  [inline] | 
Empty constructor.
Definition at line 94 of file fast_edge_estimation_3d.h.
| void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) |  [protected, virtual] | 
Implements cob_3d_features::OrganizedFeatures< PointInT, PointOutT >.
Reimplemented in cob_3d_features::FastEdgeEstimation3DOMP< PointInT, PointNT, PointOutT >.
Definition at line 102 of file fast_edge_estimation_3d.hpp.
| void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::isEdgePoint | ( | const pcl::PointCloud< PointInT > & | cloud, | 
| const PointInT & | q_point, | ||
| const std::vector< int > & | indices, | ||
| const Eigen::Vector3f & | n, | ||
| float & | strength | ||
| ) | 
Definition at line 69 of file fast_edge_estimation_3d.hpp.
| void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::setInputNormals | ( | PointCloudNConstPtr | cloud | ) |  [inline] | 
Definition at line 100 of file fast_edge_estimation_3d.h.
| PointCloudNConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::normals_  [protected] | 
Definition at line 115 of file fast_edge_estimation_3d.h.