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>
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 | |
bool | getConsistentVertexOrdering () |
Get the flag signaling consistently ordered triangle vertices. | |
std::vector< int > | getFFN () |
Get the ffn list. | |
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. | |
std::vector< int > | getSFN () |
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< nnAngle > | angles_ |
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. |
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.
typedef pcl::KdTree<PointInT> pcl::GreedyProjectionTriangulation< PointInT >::KdTree |
Reimplemented from pcl::PCLSurfaceBase< PointInT >.
typedef pcl::KdTree<PointInT>::Ptr pcl::GreedyProjectionTriangulation< PointInT >::KdTreePtr |
Reimplemented from pcl::PCLSurfaceBase< PointInT >.
typedef pcl::PointCloud<PointInT> pcl::GreedyProjectionTriangulation< PointInT >::PointCloudIn |
typedef PointCloudIn::ConstPtr pcl::GreedyProjectionTriangulation< PointInT >::PointCloudInConstPtr |
typedef PointCloudIn::Ptr pcl::GreedyProjectionTriangulation< PointInT >::PointCloudInPtr |
anonymous enum |
pcl::GreedyProjectionTriangulation< PointInT >::GreedyProjectionTriangulation | ( | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::addFringePoint | ( | int | v, |
int | s | ||
) | [inline, private] |
void pcl::GreedyProjectionTriangulation< PointInT >::addTriangle | ( | int | a, |
int | b, | ||
int | c, | ||
std::vector< pcl::Vertices > & | polygons | ||
) | [inline, private] |
void pcl::GreedyProjectionTriangulation< PointInT >::closeTriangle | ( | std::vector< pcl::Vertices > & | polygons | ) | [private] |
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.
[out] | polygons | the polygon mesh to be updated |
[in] | prev_index | index of the previous point |
[in] | next_index | index of the next point |
[in] | next_next_index | index of the point after the next one |
[in] | uvn_current | 2D coordinate of the current point |
[in] | uvn_prev | 2D coordinates of the previous point |
[in] | uvn_next | 2D coordinates of the next point |
std::string pcl::GreedyProjectionTriangulation< PointInT >::getClassName | ( | ) | const [inline, private, virtual] |
Class get name method.
Reimplemented from pcl::PCLSurfaceBase< PointInT >.
bool pcl::GreedyProjectionTriangulation< PointInT >::getConsistentVertexOrdering | ( | ) | [inline] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getFFN | ( | ) | [inline] |
double pcl::GreedyProjectionTriangulation< PointInT >::getMaximumAngle | ( | ) | [inline] |
int pcl::GreedyProjectionTriangulation< PointInT >::getMaximumNearestNeighbors | ( | ) | [inline] |
double pcl::GreedyProjectionTriangulation< PointInT >::getMaximumSurfaceAngle | ( | ) | [inline] |
double pcl::GreedyProjectionTriangulation< PointInT >::getMinimumAngle | ( | ) | [inline] |
double pcl::GreedyProjectionTriangulation< PointInT >::getMu | ( | ) | [inline] |
bool pcl::GreedyProjectionTriangulation< PointInT >::getNormalConsistency | ( | ) | [inline] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getPartIDs | ( | ) | [inline] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getPointStates | ( | ) | [inline] |
double pcl::GreedyProjectionTriangulation< PointInT >::getSearchRadius | ( | ) | [inline] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::getSFN | ( | ) | [inline] |
std::vector< std::vector< size_t > > pcl::GreedyProjectionTriangulation< PointInT >::getTriangleList | ( | const pcl::PolygonMesh & | input | ) | [private] |
static bool pcl::GreedyProjectionTriangulation< PointInT >::nnAngleSortAsc | ( | const nnAngle & | a1, |
const nnAngle & | a2 | ||
) | [inline, static, private] |
void pcl::GreedyProjectionTriangulation< PointInT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [private, virtual] |
The actual surface reconstruction method.
[out] | output | the resultant polygonal mesh |
NOTE: usually the number of triangles is around twice the number of vertices
Implements pcl::MeshConstruction< PointInT >.
void pcl::GreedyProjectionTriangulation< PointInT >::performReconstruction | ( | std::vector< pcl::Vertices > & | polygons | ) | [private, virtual] |
The actual surface reconstruction method.
[out] | polygons | the 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 >.
bool pcl::GreedyProjectionTriangulation< PointInT >::reconstructPolygons | ( | std::vector< pcl::Vertices > & | polygons | ) | [private] |
The actual surface reconstruction method.
[out] | polygons | the 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!
void pcl::GreedyProjectionTriangulation< PointInT >::setConsistentVertexOrdering | ( | bool | consistent_ordering | ) | [inline] |
Set the flag to order the resulting triangle vertices consistently (positive direction around normal).
[in] | consistent_ordering | set it to true if triangle vertices should be ordered consistently |
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumAngle | ( | double | maximum_angle | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumNearestNeighbors | ( | int | nnn | ) | [inline] |
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.
[in] | eps_angle | maximum surface angle |
void pcl::GreedyProjectionTriangulation< PointInT >::setMinimumAngle | ( | double | minimum_angle | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::setMu | ( | double | mu | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::setNormalConsistency | ( | bool | consistent | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::setSearchRadius | ( | double | radius | ) | [inline] |
bool pcl::GreedyProjectionTriangulation< PointInT >::already_connected_ [private] |
std::vector<nnAngle> pcl::GreedyProjectionTriangulation< PointInT >::angles_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::changed_1st_fn_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::changed_2nd_fn_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::consistent_ [protected] |
bool pcl::GreedyProjectionTriangulation< PointInT >::consistent_ordering_ [protected] |
std::vector<Eigen::Vector3f> pcl::GreedyProjectionTriangulation< PointInT >::coords_ [private] |
int pcl::GreedyProjectionTriangulation< PointInT >::current_index_ [private] |
double pcl::GreedyProjectionTriangulation< PointInT >::eps_angle_ [protected] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::ffn_ [private] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::fringe_queue_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::is_current_free_ [private] |
double pcl::GreedyProjectionTriangulation< PointInT >::maximum_angle_ [protected] |
double pcl::GreedyProjectionTriangulation< PointInT >::minimum_angle_ [protected] |
double pcl::GreedyProjectionTriangulation< PointInT >::mu_ [protected] |
int pcl::GreedyProjectionTriangulation< PointInT >::new2boundary_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::next_is_ffn_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::next_is_sfn_ [private] |
int pcl::GreedyProjectionTriangulation< PointInT >::nnn_ [protected] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::part_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::prev_is_ffn_ [private] |
bool pcl::GreedyProjectionTriangulation< PointInT >::prev_is_sfn_ [private] |
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::proj_qp_ [private] |
int pcl::GreedyProjectionTriangulation< PointInT >::R_ [private] |
double pcl::GreedyProjectionTriangulation< PointInT >::search_radius_ [protected] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::sfn_ [private] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::source_ [private] |
std::vector<int> pcl::GreedyProjectionTriangulation< PointInT >::state_ [private] |
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::tmp_ [private] |
pcl::Vertices pcl::GreedyProjectionTriangulation< PointInT >::triangle_ [private] |
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::u_ [private] |
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_ffn_ [private] |
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_next_ffn_ [private] |
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_next_sfn_ [private] |
Eigen::Vector2f pcl::GreedyProjectionTriangulation< PointInT >::uvn_sfn_ [private] |
Eigen::Vector3f pcl::GreedyProjectionTriangulation< PointInT >::v_ [private] |