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 | |
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< 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. | |
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.
Definition at line 50 of file gp3.h.
typedef pcl::KdTree<PointInT> pcl::GreedyProjectionTriangulation< PointInT >::KdTree |
Reimplemented from pcl::SurfaceReconstruction< PointInT >.
typedef pcl::KdTree<PointInT>::Ptr pcl::GreedyProjectionTriangulation< PointInT >::KdTreePtr |
Reimplemented from pcl::SurfaceReconstruction< 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, | |||
pcl::PolygonMesh & | output | |||
) | [inline, private] |
void pcl::GreedyProjectionTriangulation< PointInT >::closeTriangle | ( | pcl::PolygonMesh & | output | ) | [inline, private] |
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.
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
std::string pcl::GreedyProjectionTriangulation< PointInT >::getClassName | ( | ) | const [inline, private, virtual] |
Class get name method.
Reimplemented from pcl::SurfaceReconstruction< PointInT >.
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] |
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).
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) |
static bool pcl::GreedyProjectionTriangulation< PointInT >::nnAngleSortAsc | ( | const nnAngle & | a1, | |
const nnAngle & | a2 | |||
) | [inline, static, private] |
void pcl::GreedyProjectionTriangulation< PointInT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [inline, private, virtual] |
The actual urface reconstruction method.
output | the resultant polygonal mesh |
Implements pcl::SurfaceReconstruction< 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.
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 |
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumAngle | ( | double | maximum_angle | ) | [inline] |
void pcl::GreedyProjectionTriangulation< PointInT >::setMaximumNearestNeighbors | ( | int | nnn | ) | [inline] |
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.
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] |
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] |