Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
pcl::ihs::Integration Class Reference

Integrate several clouds into a common mesh. More...

#include <integration.h>

List of all members.

Public Types

typedef pcl::PointCloud
< PointXYZRGBNormal
CloudXYZRGBNormal
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr
typedef pcl::ihs::Mesh Mesh
typedef pcl::ihs::MeshConstPtr MeshConstPtr
typedef pcl::ihs::MeshPtr MeshPtr
typedef pcl::PointXYZRGBNormal PointXYZRGBNormal
typedef Mesh::VertexIndex VertexIndex
typedef Mesh::VertexIndices VertexIndices

Public Member Functions

void age (const MeshPtr &mesh, const bool cleanup=true) const
 Outlier rejection. In each merge step points that have not been observed again age by one iteration. Points that are observed again get an age of 0. Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh. A point is removed if it has not been observed from a minimum number of directions.
 Integration ()
 Constructor.
bool merge (const CloudXYZRGBNormalConstPtr &cloud_data, MeshPtr &mesh_model, const Eigen::Matrix4f &T) const
 Merge the organized cloud into the mesh.
bool reconstructMesh (const CloudXYZRGBNormalConstPtr &cloud_data, MeshPtr &mesh_model) const
 Reconstructs a mesh from an organized cloud.
void removeUnfitVertices (const MeshPtr &mesh, const bool cleanup=true) const
 Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions.
void setMaxSquaredDistance (const float squared_distance)
 Corresponding points are averaged out if their distance is below a distance threshold. Else the points are added to the mesh as new vertices (Set in cm^2).
float getMaxSquaredDistance () const
void setMaxAngle (const float angle)
 Corresponding points are only averaged out if the angle between the normals is smaller than an angle threshold.
float getMaxAngle () const
void setMaxAge (const unsigned int age)
 Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh.
unsigned int getMaxAge () const
void setMinDirections (const unsigned int directions)
 A point is removed if it has not been observed from a minimum number of directions.
unsigned int getMinDirections () const

Private Types

typedef pcl::ihs::CloudIHS CloudIHS
typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr
typedef pcl::ihs::CloudIHSPtr CloudIHSPtr
typedef pcl::PointCloud< PointXYZCloudXYZ
typedef CloudXYZ::ConstPtr CloudXYZConstPtr
typedef CloudXYZ::Ptr CloudXYZPtr
typedef pcl::KdTree< PointXYZKdTree
typedef boost::shared_ptr
< const KdTree
KdTreeConstPtr
typedef boost::shared_ptr< KdTreeKdTreePtr
typedef pcl::ihs::PointIHS PointIHS
typedef pcl::PointXYZ PointXYZ

Private Member Functions

void addToMesh (const PointIHS &pt_0, const PointIHS &pt_1, const PointIHS &pt_2, const PointIHS &pt_3, VertexIndex &vi_0, VertexIndex &vi_1, VertexIndex &vi_2, VertexIndex &vi_3, const MeshPtr &mesh) const
 Adds two triangles between points 0-1-3 and 1-2-3 to the mesh.
void addToMesh (const PointIHS &pt_0, const PointIHS &pt_1, const PointIHS &pt_2, VertexIndex &vi_0, VertexIndex &vi_1, VertexIndex &vi_2, const MeshPtr &mesh) const
 Adds a triangle between the points 0-1-2 to the mesh.
bool distanceThreshold (const PointIHS &pt_0, const PointIHS &pt_1, const PointIHS &pt_2) const
 Returns true if the distance between the three points is below a threshold.
bool distanceThreshold (const PointIHS &pt_0, const PointIHS &pt_1, const PointIHS &pt_2, const PointIHS &pt_3) const
 Returns true if the distance between the four points is below a threshold.
uint8_t trimRGB (const float val) const

Private Attributes

KdTreePtr kd_tree_
 Nearest neighbor search.
unsigned int max_age_
 Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh.
float max_angle_
 Maximum angle between normals below which points are averaged out. In degrees.
float max_squared_distance_
 Maximum squared distance below which points are averaged out.
unsigned int min_directions_
 A point is removed if it has not been observed from a minimum number of directions.
float min_weight_
 Minimum weight above which points are added.

Detailed Description

Integrate several clouds into a common mesh.

Author:
Martin Saelzle

Definition at line 71 of file integration.h.


Member Typedef Documentation

Definition at line 163 of file integration.h.

Definition at line 165 of file integration.h.

Definition at line 164 of file integration.h.

Definition at line 158 of file integration.h.

Definition at line 160 of file integration.h.

Definition at line 159 of file integration.h.

Definition at line 76 of file integration.h.

Definition at line 78 of file integration.h.

Definition at line 77 of file integration.h.

Definition at line 167 of file integration.h.

typedef boost::shared_ptr<const KdTree> pcl::ihs::Integration::KdTreeConstPtr [private]

Definition at line 169 of file integration.h.

typedef boost::shared_ptr<KdTree> pcl::ihs::Integration::KdTreePtr [private]

Definition at line 168 of file integration.h.

Definition at line 80 of file integration.h.

typedef pcl::ihs::MeshConstPtr pcl::ihs::Integration::MeshConstPtr

Definition at line 82 of file integration.h.

Definition at line 81 of file integration.h.

Definition at line 162 of file integration.h.

Definition at line 157 of file integration.h.

Definition at line 75 of file integration.h.

Definition at line 83 of file integration.h.

Definition at line 84 of file integration.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 54 of file integration.cpp.


Member Function Documentation

void pcl::ihs::Integration::addToMesh ( const PointIHS pt_0,
const PointIHS pt_1,
const PointIHS pt_2,
const PointIHS pt_3,
VertexIndex vi_0,
VertexIndex vi_1,
VertexIndex vi_2,
VertexIndex vi_3,
const MeshPtr mesh 
) const [private]

Adds two triangles between points 0-1-3 and 1-2-3 to the mesh.

Definition at line 507 of file integration.cpp.

void pcl::ihs::Integration::addToMesh ( const PointIHS pt_0,
const PointIHS pt_1,
const PointIHS pt_2,
VertexIndex vi_0,
VertexIndex vi_1,
VertexIndex vi_2,
const MeshPtr mesh 
) const [private]

Adds a triangle between the points 0-1-2 to the mesh.

Definition at line 554 of file integration.cpp.

void pcl::ihs::Integration::age ( const MeshPtr mesh,
const bool  cleanup = true 
) const

Outlier rejection. In each merge step points that have not been observed again age by one iteration. Points that are observed again get an age of 0. Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh. A point is removed if it has not been observed from a minimum number of directions.

Parameters:
[in,out]meshThe mesh which should be processed.
[in]cleanupCalls mesh.cleanup () if true.

Definition at line 389 of file integration.cpp.

bool pcl::ihs::Integration::distanceThreshold ( const PointIHS pt_0,
const PointIHS pt_1,
const PointIHS pt_2 
) const [private]

Returns true if the distance between the three points is below a threshold.

Definition at line 577 of file integration.cpp.

bool pcl::ihs::Integration::distanceThreshold ( const PointIHS pt_0,
const PointIHS pt_1,
const PointIHS pt_2,
const PointIHS pt_3 
) const [private]

Returns true if the distance between the four points is below a threshold.

Definition at line 590 of file integration.cpp.

unsigned int pcl::ihs::Integration::getMaxAge ( ) const

Definition at line 477 of file integration.cpp.

Definition at line 463 of file integration.cpp.

Definition at line 449 of file integration.cpp.

Definition at line 491 of file integration.cpp.

bool pcl::ihs::Integration::merge ( const CloudXYZRGBNormalConstPtr cloud_data,
MeshPtr mesh_model,
const Eigen::Matrix4f &  T 
) const

Merge the organized cloud into the mesh.

Parameters:
[in]cloud_dataInput cloud. Must be organized.
[in,out]mesh_modelMesh with new points integrated.
[in]TTransformation that aligns the data cloud with the model mesh.
Returns:
true if success.

Definition at line 185 of file integration.cpp.

bool pcl::ihs::Integration::reconstructMesh ( const CloudXYZRGBNormalConstPtr cloud_data,
MeshPtr mesh_model 
) const

Reconstructs a mesh from an organized cloud.

Parameters:
[in]cloud_dataInput cloud. Must be organized.
[in]mesh_modelReconstructed mesh.
Returns:
true if success.

Definition at line 67 of file integration.cpp.

void pcl::ihs::Integration::removeUnfitVertices ( const MeshPtr mesh,
const bool  cleanup = true 
) const

Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions.

Parameters:
[in,out]meshThe which should be processed.
[in]cleanupCalls mesh.cleanup () if true.

Definition at line 423 of file integration.cpp.

void pcl::ihs::Integration::setMaxAge ( const unsigned int  age)

Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh.

Note:
Must be greater than zero.

Definition at line 471 of file integration.cpp.

void pcl::ihs::Integration::setMaxAngle ( const float  angle)

Corresponding points are only averaged out if the angle between the normals is smaller than an angle threshold.

Note:
Must be between 0 and 180. Values outside this range are clamped to the nearest valid value.

Definition at line 457 of file integration.cpp.

void pcl::ihs::Integration::setMaxSquaredDistance ( const float  squared_distance)

Corresponding points are averaged out if their distance is below a distance threshold. Else the points are added to the mesh as new vertices (Set in cm^2).

Note:
Must be greater than zero.

Definition at line 443 of file integration.cpp.

void pcl::ihs::Integration::setMinDirections ( const unsigned int  directions)

A point is removed if it has not been observed from a minimum number of directions.

Note:
Must be greater than zero.

Definition at line 485 of file integration.cpp.

uint8_t pcl::ihs::Integration::trimRGB ( const float  val) const [private]

Definition at line 499 of file integration.cpp.


Member Data Documentation

Nearest neighbor search.

Definition at line 214 of file integration.h.

unsigned int pcl::ihs::Integration::max_age_ [private]

Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh.

Definition at line 226 of file integration.h.

Maximum angle between normals below which points are averaged out. In degrees.

Definition at line 220 of file integration.h.

Maximum squared distance below which points are averaged out.

Definition at line 217 of file integration.h.

A point is removed if it has not been observed from a minimum number of directions.

Definition at line 229 of file integration.h.

Minimum weight above which points are added.

Definition at line 223 of file integration.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:58