Classes | Public Types | Public Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes
pcl::GreedyProjectionTriangulation< PointInT > Class Template Reference

GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between areas with different point densities. More...

#include <gp3.h>

Inheritance diagram for pcl::GreedyProjectionTriangulation< PointInT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  doubleEdge
 Struct for storing the edges starting from a fringe point. More...
struct  nnAngle
 Struct for storing the angles to nearest neighbors. More...

Public Types

typedef boost::shared_ptr
< const
GreedyProjectionTriangulation
< PointInT > > 
ConstPtr
enum  GP3Type {
  NONE = -1, FREE = 0, FRINGE = 1, BOUNDARY = 2,
  COMPLETED = 3
}
typedef pcl::KdTree< PointInT > KdTree
typedef pcl::KdTree< PointInT >
::Ptr 
KdTreePtr
typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef boost::shared_ptr
< GreedyProjectionTriangulation
< PointInT > > 
Ptr

Public Member Functions

bool getConsistentVertexOrdering () const
 Get the flag signaling consistently ordered triangle vertices.
std::vector< int > getFFN () const
 Get the ffn list.
double getMaximumAngle () const
 Get the parameter for distance based weighting of neighbors.
int getMaximumNearestNeighbors () const
 Get the maximum number of nearest neighbors to be searched for.
double getMaximumSurfaceAngle () const
 Get the maximum surface angle.
double getMinimumAngle () const
 Get the parameter for distance based weighting of neighbors.
double getMu () const
 Get the nearest neighbor distance multiplier.
bool getNormalConsistency () const
 Get the flag for consistently oriented normals.
std::vector< int > getPartIDs () const
 Get the ID of each point after reconstruction.
std::vector< int > getPointStates () const
 Get the state of each point after reconstruction.
double getSearchRadius () const
 Get the sphere radius used for determining the k-nearest neighbors.
std::vector< int > getSFN () const
 Get the sfn list.
 GreedyProjectionTriangulation ()
 Empty constructor.
void setConsistentVertexOrdering (bool consistent_ordering)
 Set the flag to order the resulting triangle vertices consistently (positive direction around normal).
void setMaximumAngle (double maximum_angle)
 Set the maximum angle each triangle can have.
void setMaximumNearestNeighbors (int nnn)
 Set the maximum number of nearest neighbors to be searched for.
void setMaximumSurfaceAngle (double eps_angle)
 Don't consider points for triangulation if their normal deviates more than this value from the query point's normal.
void setMinimumAngle (double minimum_angle)
 Set the minimum angle each triangle should have.
void setMu (double mu)
 Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point (this will make the algorithm adapt to different point densities in the cloud).
void setNormalConsistency (bool consistent)
 Set the flag if the input normals are oriented consistently.
void setSearchRadius (double radius)
 Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulating.

Protected Attributes

bool consistent_
 Set this to true if the normals of the input are consistently oriented.
bool consistent_ordering_
 Set this to true if the output triangle vertices should be consistently oriented.
double eps_angle_
 Maximum surface angle.
double maximum_angle_
 The maximum angle for the triangles.
double minimum_angle_
 The preferred minimum angle for the triangles.
double mu_
 The nearest neighbor distance multiplier to obtain the final search radius.
int nnn_
 The maximum number of nearest neighbors accepted by searching.
double search_radius_
 The nearest neighbors search radius for each point and the maximum edge length.

Private Member Functions

void addFringePoint (int v, int s)
 Add a new vertex to the advancing edge front and set its source point.
void addTriangle (int a, int b, int c, std::vector< pcl::Vertices > &polygons)
 Add a new triangle to the current polygon mesh.
void closeTriangle (std::vector< pcl::Vertices > &polygons)
 Whenever a query point is part of a boundary loop containing 3 points, that triangle is created (called if angle constraints make it possible)
void connectPoint (std::vector< pcl::Vertices > &polygons, const int prev_index, const int next_index, const int next_next_index, const Eigen::Vector2f &uvn_current, const Eigen::Vector2f &uvn_prev, const Eigen::Vector2f &uvn_next)
 Forms a new triangle by connecting the current neighbor to the query point and the previous neighbor.
std::string getClassName () const
 Class get name method.
std::vector< std::vector
< size_t > > 
getTriangleList (const pcl::PolygonMesh &input)
 Get the list of containing triangles for each vertex in a PolygonMesh.
void performReconstruction (pcl::PolygonMesh &output)
 The actual surface reconstruction method.
void performReconstruction (std::vector< pcl::Vertices > &polygons)
 The actual surface reconstruction method.
bool reconstructPolygons (std::vector< pcl::Vertices > &polygons)
 The actual surface reconstruction method.

Static Private Member Functions

static bool nnAngleSortAsc (const nnAngle &a1, const nnAngle &a2)
 Function for ascending sort of nnAngle, taking visibility into account (angles to visible neighbors will be first, to the invisible ones after).

Private Attributes

bool already_connected_
 Flag to set if the next neighbor was already connected in the previous step. To avoid inconsistency it should not be connected again.
std::vector< nnAngleangles_
 A list of angles to neighbors.
bool changed_1st_fn_
 Flag to set if the first fringe neighbor was changed.
bool changed_2nd_fn_
 Flag to set if the second fringe neighbor was changed.
std::vector< Eigen::Vector3f > coords_
 Temporary variable to store point coordinates.
int current_index_
 Current point's index.
std::vector< int > ffn_
 List of fringe neighbors in one direction.
std::vector< int > fringe_queue_
 Points on the outer edge from which the mesh has to be grown.
bool is_current_free_
 Flag to set if the current point is free.
int new2boundary_
 New boundary point.
bool next_is_ffn_
 Flag to set if the next point is the first fringe neighbor.
bool next_is_sfn_
 Flag to set if the next point is the second fringe neighbor.
std::vector< int > part_
 Connected component labels for each point.
bool prev_is_ffn_
 Flag to set if the previous point is the first fringe neighbor.
bool prev_is_sfn_
 Flag to set if the next point is the second fringe neighbor.
Eigen::Vector3f proj_qp_
 Point coordinates projected onto the plane defined by the point normal.
int R_
 Index of the current query point.
std::vector< int > sfn_
 List of fringe neighbors in other direction.
std::vector< int > source_
 List of sources.
std::vector< int > state_
 List of point states.
Eigen::Vector3f tmp_
 Temporary variable to store 3 coordiantes.
pcl::Vertices triangle_
 Temporary variable to store a triangle (as a set of point indices)
Eigen::Vector3f u_
 First coordinate vector of the 2D coordinate frame.
Eigen::Vector2f uvn_ffn_
 2D coordinates of the first fringe neighbor
Eigen::Vector2f uvn_next_ffn_
 2D coordinates of the first fringe neighbor of the next point
Eigen::Vector2f uvn_next_sfn_
 2D coordinates of the second fringe neighbor of the next point
Eigen::Vector2f uvn_sfn_
 2D coordinates of the second fringe neighbor
Eigen::Vector3f v_
 Second coordinate vector of the 2D coordinate frame.

Detailed Description

template<typename PointInT>
class pcl::GreedyProjectionTriangulation< PointInT >

GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between areas with different point densities.

Author:
Zoltan Csaba Marton

Definition at line 138 of file gp3.h.


Member Typedef Documentation

template<typename PointInT>
typedef boost::shared_ptr<const GreedyProjectionTriangulation<PointInT> > pcl::GreedyProjectionTriangulation< PointInT >::ConstPtr

Reimplemented from pcl::MeshConstruction< PointInT >.

Definition at line 142 of file gp3.h.

template<typename PointInT>
typedef pcl::KdTree<PointInT> pcl::GreedyProjectionTriangulation< PointInT >::KdTree

Reimplemented from pcl::PCLSurfaceBase< PointInT >.

Definition at line 148 of file gp3.h.

template<typename PointInT>
typedef pcl::KdTree<PointInT>::Ptr pcl::GreedyProjectionTriangulation< PointInT >::KdTreePtr

Reimplemented from pcl::PCLSurfaceBase< PointInT >.

Definition at line 149 of file gp3.h.

template<typename PointInT>
typedef pcl::PointCloud<PointInT> pcl::GreedyProjectionTriangulation< PointInT >::PointCloudIn

Definition at line 151 of file gp3.h.

template<typename PointInT>
typedef PointCloudIn::ConstPtr pcl::GreedyProjectionTriangulation< PointInT >::PointCloudInConstPtr

Definition at line 153 of file gp3.h.

template<typename PointInT>
typedef PointCloudIn::Ptr pcl::GreedyProjectionTriangulation< PointInT >::PointCloudInPtr

Definition at line 152 of file gp3.h.

template<typename PointInT>
typedef boost::shared_ptr<GreedyProjectionTriangulation<PointInT> > pcl::GreedyProjectionTriangulation< PointInT >::Ptr

Reimplemented from pcl::MeshConstruction< PointInT >.

Definition at line 141 of file gp3.h.


Member Enumeration Documentation

template<typename PointInT>
enum pcl::GreedyProjectionTriangulation::GP3Type
Enumerator:
NONE 
FREE 
FRINGE 
BOUNDARY 
COMPLETED 

Definition at line 155 of file gp3.h.


Constructor & Destructor Documentation

template<typename PointInT>
pcl::GreedyProjectionTriangulation< PointInT >::GreedyProjectionTriangulation ( ) [inline]

Empty constructor.

Definition at line 165 of file gp3.h.


Member Function Documentation

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::addFringePoint ( int  v,
int  s 
) [inline, private]

Add a new vertex to the advancing edge front and set its source point.

Parameters:
[in]vindex of the vertex that was connected
[in]sindex of the source point

Definition at line 519 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::addTriangle ( int  a,
int  b,
int  c,
std::vector< pcl::Vertices > &  polygons 
) [inline, private]

Add a new triangle to the current polygon mesh.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex
[out]polygonsthe polygon mesh to be updated

Definition at line 483 of file gp3.h.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::closeTriangle ( std::vector< pcl::Vertices > &  polygons) [private]

Whenever a query point is part of a boundary loop containing 3 points, that triangle is created (called if angle constraints make it possible)

Parameters:
[out]polygonsthe polygon mesh to be updated

Definition at line 1060 of file gp3.hpp.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::connectPoint ( std::vector< pcl::Vertices > &  polygons,
const int  prev_index,
const int  next_index,
const int  next_next_index,
const Eigen::Vector2f &  uvn_current,
const Eigen::Vector2f &  uvn_prev,
const Eigen::Vector2f &  uvn_next 
) [private]

Forms a new triangle by connecting the current neighbor to the query point and the previous neighbor.

Parameters:
[out]polygonsthe polygon mesh to be updated
[in]prev_indexindex of the previous point
[in]next_indexindex of the next point
[in]next_next_indexindex of the point after the next one
[in]uvn_current2D coordinate of the current point
[in]uvn_prev2D coordinates of the previous point
[in]uvn_next2D coordinates of the next point

Definition at line 1093 of file gp3.hpp.

template<typename PointInT>
std::string pcl::GreedyProjectionTriangulation< PointInT >::getClassName ( ) const [inline, private, virtual]

Class get name method.

Reimplemented from pcl::PCLSurfaceBase< PointInT >.

Definition at line 442 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::getConsistentVertexOrdering ( ) const [inline]

Get the flag signaling consistently ordered triangle vertices.

Definition at line 289 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getFFN ( ) const [inline]

Get the ffn list.

Definition at line 310 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::getMaximumAngle ( ) const [inline]

Get the parameter for distance based weighting of neighbors.

Definition at line 256 of file gp3.h.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::getMaximumNearestNeighbors ( ) const [inline]

Get the maximum number of nearest neighbors to be searched for.

Definition at line 223 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::getMaximumSurfaceAngle ( ) const [inline]

Get the maximum surface angle.

Definition at line 268 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::getMinimumAngle ( ) const [inline]

Get the parameter for distance based weighting of neighbors.

Definition at line 245 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::getMu ( ) const [inline]

Get the nearest neighbor distance multiplier.

Definition at line 213 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::getNormalConsistency ( ) const [inline]

Get the flag for consistently oriented normals.

Definition at line 278 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getPartIDs ( ) const [inline]

Get the ID of each point after reconstruction.

Note:
parts are numbered from 0, a -1 denotes unconnected points

Definition at line 301 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getPointStates ( ) const [inline]

Get the state of each point after reconstruction.

Note:
Options are defined as constants: FREE, FRINGE, COMPLETED, BOUNDARY and NONE

Definition at line 295 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::getSearchRadius ( ) const [inline]

Get the sphere radius used for determining the k-nearest neighbors.

Definition at line 234 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getSFN ( ) const [inline]

Get the sfn list.

Definition at line 306 of file gp3.h.

template<typename PointInT >
std::vector< std::vector< size_t > > pcl::GreedyProjectionTriangulation< PointInT >::getTriangleList ( const pcl::PolygonMesh input) [private]

Get the list of containing triangles for each vertex in a PolygonMesh.

Parameters:
[in]polygonMeshthe input polygon mesh

Definition at line 1666 of file gp3.hpp.

template<typename PointInT>
static bool pcl::GreedyProjectionTriangulation< PointInT >::nnAngleSortAsc ( const nnAngle a1,
const nnAngle a2 
) [inline, static, private]

Function for ascending sort of nnAngle, taking visibility into account (angles to visible neighbors will be first, to the invisible ones after).

Parameters:
[in]a1the first angle
[in]a2the second angle

Definition at line 532 of file gp3.h.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::performReconstruction ( pcl::PolygonMesh output) [private, virtual]

The actual surface reconstruction method.

Parameters:
[out]outputthe resultant polygonal mesh

NOTE: usually the number of triangles is around twice the number of vertices

Implements pcl::MeshConstruction< PointInT >.

Definition at line 46 of file gp3.hpp.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::performReconstruction ( std::vector< pcl::Vertices > &  polygons) [private, virtual]

The actual surface reconstruction method.

Parameters:
[out]polygonsthe resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.

NOTE: usually the number of triangles is around twice the number of vertices

Implements pcl::MeshConstruction< PointInT >.

Definition at line 61 of file gp3.hpp.

template<typename PointInT >
bool pcl::GreedyProjectionTriangulation< PointInT >::reconstructPolygons ( std::vector< pcl::Vertices > &  polygons) [private]

The actual surface reconstruction method.

Parameters:
[out]polygonsthe resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.

NOTE: discarding NaN points and those that are not in indices_

NOTE: discarding NaN points and those that are not in indices_

NOTE: nnIdx was reset

TODO: document!

Definition at line 74 of file gp3.hpp.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setConsistentVertexOrdering ( bool  consistent_ordering) [inline]

Set the flag to order the resulting triangle vertices consistently (positive direction around normal).

Note:
Assumes consistently oriented normals (towards the viewpoint) -- see setNormalConsistency ()
Parameters:
[in]consistent_orderingset it to true if triangle vertices should be ordered consistently

Definition at line 285 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumAngle ( double  maximum_angle) [inline]

Set the maximum angle each triangle can have.

Parameters:
[in]maximum_anglethe maximum angle each triangle can have
Note:
For best results, its value should be around 120 degrees

Definition at line 252 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumNearestNeighbors ( int  nnn) [inline]

Set the maximum number of nearest neighbors to be searched for.

Parameters:
[in]nnnthe maximum number of nearest neighbors

Definition at line 219 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumSurfaceAngle ( double  eps_angle) [inline]

Don't consider points for triangulation if their normal deviates more than this value from the query point's normal.

Parameters:
[in]eps_anglemaximum surface angle
Note:
As normal estimation methods usually give smooth transitions at sharp edges, this ensures correct triangulation by avoiding connecting points from one side to points from the other through forcing the use of the edge points.

Definition at line 264 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMinimumAngle ( double  minimum_angle) [inline]

Set the minimum angle each triangle should have.

Parameters:
[in]minimum_anglethe minimum angle each triangle should have
Note:
As this is a greedy approach, this will have to be violated from time to time

Definition at line 241 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMu ( double  mu) [inline]

Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point (this will make the algorithm adapt to different point densities in the cloud).

Parameters:
[in]muthe multiplier

Definition at line 209 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setNormalConsistency ( bool  consistent) [inline]

Set the flag if the input normals are oriented consistently.

Parameters:
[in]consistentset it to true if the normals are consistently oriented

Definition at line 274 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setSearchRadius ( double  radius) [inline]

Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulating.

Parameters:
[in]radiusthe sphere radius that is to contain all k-nearest neighbors
Note:
This distance limits the maximum edge length!

Definition at line 230 of file gp3.h.


Member Data Documentation

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::already_connected_ [private]

Flag to set if the next neighbor was already connected in the previous step. To avoid inconsistency it should not be connected again.

Definition at line 402 of file gp3.h.

template<typename PointInT>
std::vector<nnAngle> pcl::GreedyProjectionTriangulation< PointInT >::angles_ [private]

A list of angles to neighbors.

Definition at line 364 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::changed_1st_fn_ [private]

Flag to set if the first fringe neighbor was changed.

Definition at line 393 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::changed_2nd_fn_ [private]

Flag to set if the second fringe neighbor was changed.

Definition at line 395 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::consistent_ [protected]

Set this to true if the normals of the input are consistently oriented.

Definition at line 332 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::consistent_ordering_ [protected]

Set this to true if the output triangle vertices should be consistently oriented.

Definition at line 335 of file gp3.h.

template<typename PointInT>
std::vector<Eigen::Vector3f> pcl::GreedyProjectionTriangulation< PointInT >::coords_ [private]

Temporary variable to store point coordinates.

Definition at line 361 of file gp3.h.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::current_index_ [private]

Current point's index.

Definition at line 383 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::eps_angle_ [protected]

Maximum surface angle.

Definition at line 329 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::ffn_ [private]

List of fringe neighbors in one direction.

Definition at line 372 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::fringe_queue_ [private]

Points on the outer edge from which the mesh has to be grown.

Definition at line 378 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::is_current_free_ [private]

Flag to set if the current point is free.

Definition at line 381 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::maximum_angle_ [protected]

The maximum angle for the triangles.

Definition at line 326 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::minimum_angle_ [protected]

The preferred minimum angle for the triangles.

Definition at line 323 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::mu_ [protected]

The nearest neighbor distance multiplier to obtain the final search radius.

Definition at line 314 of file gp3.h.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::new2boundary_ [private]

New boundary point.

Definition at line 397 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::next_is_ffn_ [private]

Flag to set if the next point is the first fringe neighbor.

Definition at line 389 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::next_is_sfn_ [private]

Flag to set if the next point is the second fringe neighbor.

Definition at line 391 of file gp3.h.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::nnn_ [protected]

The maximum number of nearest neighbors accepted by searching.

Definition at line 320 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::part_ [private]

Connected component labels for each point.

Definition at line 376 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::prev_is_ffn_ [private]

Flag to set if the previous point is the first fringe neighbor.

Definition at line 385 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::prev_is_sfn_ [private]

Flag to set if the next point is the second fringe neighbor.

Definition at line 387 of file gp3.h.

template<typename PointInT>
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::proj_qp_ [private]

Point coordinates projected onto the plane defined by the point normal.

Definition at line 405 of file gp3.h.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::R_ [private]

Index of the current query point.

Definition at line 366 of file gp3.h.

template<typename PointInT>
double pcl::GreedyProjectionTriangulation< PointInT >::search_radius_ [protected]

The nearest neighbors search radius for each point and the maximum edge length.

Definition at line 317 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::sfn_ [private]

List of fringe neighbors in other direction.

Definition at line 374 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::source_ [private]

List of sources.

Definition at line 370 of file gp3.h.

template<typename PointInT>
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::state_ [private]

List of point states.

Definition at line 368 of file gp3.h.

template<typename PointInT>
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::tmp_ [private]

Temporary variable to store 3 coordiantes.

Definition at line 420 of file gp3.h.

template<typename PointInT>
pcl::Vertices pcl::GreedyProjectionTriangulation< PointInT >::triangle_ [private]

Temporary variable to store a triangle (as a set of point indices)

Definition at line 359 of file gp3.h.

template<typename PointInT>
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::u_ [private]

First coordinate vector of the 2D coordinate frame.

Definition at line 407 of file gp3.h.

template<typename PointInT>
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_ffn_ [private]

2D coordinates of the first fringe neighbor

Definition at line 411 of file gp3.h.

template<typename PointInT>
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_next_ffn_ [private]

2D coordinates of the first fringe neighbor of the next point

Definition at line 415 of file gp3.h.

template<typename PointInT>
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_next_sfn_ [private]

2D coordinates of the second fringe neighbor of the next point

Definition at line 417 of file gp3.h.

template<typename PointInT>
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_sfn_ [private]

2D coordinates of the second fringe neighbor

Definition at line 413 of file gp3.h.

template<typename PointInT>
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::v_ [private]

Second coordinate vector of the 2D coordinate frame.

Definition at line 409 of file gp3.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:32