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

enum  {
  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

Public Member Functions

double getMaximumAngle ()
 Get the parameter for distance based weighting of neighbors.
int getMaximumNearestNeighbors ()
 Get the maximum number of nearest neighbors to be searched for.
double getMaximumSurfaceAngle ()
 Get the maximum surface angle.
double getMinimumAngle ()
 Get the parameter for distance based weighting of neighbors.
double getMu ()
 Get the nearest neighbor distance multiplier.
bool getNormalConsistency ()
 Get the flag for consistently oriented normals.
std::vector< int > getPartIDs ()
 Get the ID of each point after reconstruction.
std::vector< int > getPointStates ()
 Get the state of each point after reconstruction.
double getSearchRadius ()
 Get the sphere radius used for determining the k-nearest neighbors.
 GreedyProjectionTriangulation ()
 Empty constructor.
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 setMaximumSurfaceAgle (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 for consistently oriented normals.
void setSearchRadius (double radius)
 Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulating.

Protected Member Functions

int searchForNeighbors (int index, std::vector< int > &indices, std::vector< float > &distances)
 Search for the nnn_ nearest neighbors of a given point.

Protected Attributes

bool consistent_
 Set this to true if the normals of the input are 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, pcl::PolygonMesh &output)
 Add a new triangle to the current polygon mesh.
void closeTriangle (pcl::PolygonMesh &output)
 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 (pcl::PolygonMesh &output, 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.
bool isVisible (const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2, const Eigen::Vector2f &R=Eigen::Vector2f::Zero())
 Returns if a point X is visible from point R when taking into account the segment S1,S2 (use the print parameter to enable output of debug messages).
void performReconstruction (pcl::PolygonMesh &output)
 The actual urface reconstruction method.

Static Private Member Functions

static bool nnAngleSortAsc (const nnAngle &a1, const nnAngle &a2)
 Function for ascending sort of nnAngle.

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.
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 50 of file gp3.h.


Member Typedef Documentation

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

Reimplemented from pcl::SurfaceReconstruction< PointInT >.

Definition at line 50 of file gp3.h.

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

Reimplemented from pcl::SurfaceReconstruction< PointInT >.

Definition at line 51 of file gp3.h.

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

Definition at line 53 of file gp3.h.

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

Definition at line 55 of file gp3.h.

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

Definition at line 54 of file gp3.h.


Member Enumeration Documentation

template<typename PointInT>
anonymous enum
Enumerator:
NONE 
FREE 
FRINGE 
BOUNDARY 
COMPLETED 

Definition at line 59 of file gp3.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 68 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:
v index of the vertex that was connected
s index of the source point

Definition at line 338 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::addTriangle ( int  a,
int  b,
int  c,
pcl::PolygonMesh output 
) [inline, private]

Add a new triangle to the current polygon mesh.

Parameters:
a index of the first vertex
b index of the second vertex
c index of the third vertex
output the polygon mesh to be updated

Definition at line 324 of file gp3.h.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::closeTriangle ( pcl::PolygonMesh output  )  [inline, 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:
output the polygon mesh to be updated

Definition at line 993 of file gp3.hpp.

template<typename PointInT >
void pcl::GreedyProjectionTriangulation< PointInT >::connectPoint ( pcl::PolygonMesh output,
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 
) [inline, private]

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

Parameters:
output the polygon mesh to be updated
prev_index index of the previous point
next_index index of the next point
next_next_index index of the point after the next one
uvn_current 2D coordinate of the current point
uvn_prev 2D coordinates of the previous point
uvn_next 2D coordinates of the next point

should be never the case

a clear case

a clear case

straightforward cases

messed up cases

updating prev_index

updating ffn

updating current

updating prev_index

updating sfn

updating current

updating next_index

ffn[next_index]

sfn[next_index]

updating ffn

updating current

updating next_index

ffn[next_index]

sfn[next_index]

updating sfn

Definition at line 1029 of file gp3.hpp.

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

Class get name method.

Reimplemented from pcl::SurfaceReconstruction< PointInT >.

Definition at line 289 of file gp3.h.

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

Get the parameter for distance based weighting of neighbors.

Definition at line 125 of file gp3.h.

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

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

Definition at line 92 of file gp3.h.

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

Get the maximum surface angle.

Definition at line 137 of file gp3.h.

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

Get the parameter for distance based weighting of neighbors.

Definition at line 114 of file gp3.h.

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

Get the nearest neighbor distance multiplier.

Definition at line 82 of file gp3.h.

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

Get the flag for consistently oriented normals.

Definition at line 147 of file gp3.h.

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

Get the ID of each point after reconstruction.

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

Definition at line 159 of file gp3.h.

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

Get the state of each point after reconstruction.

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

Definition at line 153 of file gp3.h.

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

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

Definition at line 103 of file gp3.h.

template<typename PointInT>
bool pcl::GreedyProjectionTriangulation< PointInT >::isVisible ( const Eigen::Vector2f &  X,
const Eigen::Vector2f &  S1,
const Eigen::Vector2f &  S2,
const Eigen::Vector2f &  R = Eigen::Vector2f::Zero () 
) [inline, private]

Returns if a point X is visible from point R when taking into account the segment S1,S2 (use the print parameter to enable output of debug messages).

Parameters:
X 2D coordinate of the point
S1 2D coordinate of the segment's first point
S2 2D coordinate of the segment's secont point
R 2D coorddinate of the reference point (defaults to 0,0)

Definition at line 366 of file gp3.h.

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

Function for ascending sort of nnAngle.

Parameters:
a1 the first angle
a2 the second angle

Definition at line 350 of file gp3.h.

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

The actual urface reconstruction method.

Parameters:
output the resultant polygonal mesh

Implements pcl::SurfaceReconstruction< PointInT >.

Definition at line 45 of file gp3.hpp.

template<typename PointInT>
int pcl::GreedyProjectionTriangulation< PointInT >::searchForNeighbors ( int  index,
std::vector< int > &  indices,
std::vector< float > &  distances 
) [inline, protected]

Search for the nnn_ nearest neighbors of a given point.

Parameters:
index the index of the query point
indices the resultant vector of indices representing the k-nearest neighbors
distances the resultant distances from the query point to the k-nearest neighbors
Note:
The final neighborhood will be limited by the search radius, but we need the maximal set of neighbors for increasing the chance of determining the direction of the advancing front (see the "source" array) -- adds no overhead.

Definition at line 192 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:
maximum_angle the maximum angle each triangle can have
Note:
For best results, its value should be around 120 degrees

Definition at line 121 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:
nnn the maximum number of nearest neighbors

Definition at line 88 of file gp3.h.

template<typename PointInT>
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumSurfaceAgle ( 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:
eps_angle maximum 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 133 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:
minimum_angle the 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 110 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:
mu the multiplier

Definition at line 78 of file gp3.h.

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

Set the flag for consistently oriented normals.

Parameters:
consistent set it to true if the normals are consistently oriented

Definition at line 143 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:
radius the sphere radius that is to contain all k-nearest neighbors
Note:
This distance limits the maximum edge length!

Definition at line 99 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 261 of file gp3.h.

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

A list of angles to neighbors.

Definition at line 223 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 252 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 254 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 181 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 220 of file gp3.h.

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

Current point's index.

Definition at line 242 of file gp3.h.

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

Maximum surface angle.

Definition at line 178 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 231 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 237 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 240 of file gp3.h.

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

The maximum angle for the triangles.

Definition at line 175 of file gp3.h.

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

The preferred minimum angle for the triangles.

Definition at line 172 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 166 of file gp3.h.

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

New boundary point.

Definition at line 256 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 248 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 250 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 163 of file gp3.h.

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

Connected component labels for each point.

Definition at line 235 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 244 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 246 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 264 of file gp3.h.

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

Index of the current query point.

Definition at line 225 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 169 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 233 of file gp3.h.

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

List of sources.

Definition at line 229 of file gp3.h.

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

List of point states.

Definition at line 227 of file gp3.h.

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

Temporary variable to store 3 coordiantes.

Definition at line 279 of file gp3.h.

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

Temporary variable to store a triangle.

Definition at line 218 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 266 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 270 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 274 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 276 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 272 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 268 of file gp3.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:18 2013