Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular mesh. More...
#include <organized_fast_mesh.h>
Public Types | |
typedef pcl::PointCloud < PointInT >::Ptr | PointCloudPtr |
typedef std::vector < pcl::Vertices > | Polygons |
enum | TriangulationType { TRIANGLE_RIGHT_CUT, TRIANGLE_LEFT_CUT, TRIANGLE_ADAPTIVE_CUT, QUAD_MESH } |
Public Member Functions | |
OrganizedFastMesh () | |
Constructor. Triangulation type defaults to QUAD_MESH. | |
void | setMaxEdgeLength (float max_edge_length) |
Set a maximum edge length. TODO: Implement! | |
void | setTrianglePixelSize (int triangle_size) |
Set the edge length (in pixels) used for constructing the fixed mesh. | |
void | setTriangulationType (TriangulationType type) |
Set the triangulation type (see TriangulationType) | |
void | storeShadowedFaces (bool enable) |
Store shadowed faces or not. | |
~OrganizedFastMesh () | |
Destructor. | |
Protected Member Functions | |
void | addQuad (int a, int b, int c, int d, int idx, std::vector< pcl::Vertices > &polygons) |
Add a new quad to the current polygon mesh. | |
void | addTriangle (int a, int b, int c, int idx, std::vector< pcl::Vertices > &polygons) |
Add a new triangle to the current polygon mesh. | |
bool | isShadowed (const PointInT &point_a, const PointInT &point_b) |
Check if a point is shadowed by another point. | |
bool | isShadowedQuad (const int &a, const int &b, const int &c, const int &d) |
Check if a triangle is shadowed. | |
bool | isShadowedTriangle (const int &a, const int &b, const int &c) |
Check if a triangle is shadowed. | |
bool | isValidQuad (const int &a, const int &b, const int &c, const int &d) |
Check if a quad is valid. | |
bool | isValidTriangle (const int &a, const int &b, const int &c) |
Check if a triangle is valid. | |
void | makeAdaptiveCutMesh (std::vector< pcl::Vertices > &polygons) |
Create an adaptive cut mesh. | |
void | makeLeftCutMesh (std::vector< pcl::Vertices > &polygons) |
Create a left cut mesh. | |
void | makeQuadMesh (std::vector< pcl::Vertices > &polygons) |
Create a quad mesh. | |
void | makeRightCutMesh (std::vector< pcl::Vertices > &polygons) |
Create a right cut mesh. | |
virtual void | performReconstruction (std::vector< pcl::Vertices > &polygons) |
Create the surface. | |
void | performReconstruction (pcl::PolygonMesh &output) |
Create the surface. | |
void | reconstructPolygons (std::vector< pcl::Vertices > &polygons) |
Perform the actual polygonal reconstruction. | |
void | resetPointData (const int &point_index, pcl::PolygonMesh &mesh, const float &value=0.0f, int field_x_idx=0, int field_y_idx=1, int field_z_idx=2) |
Set (all) coordinates of a particular point to the specified value. | |
Protected Attributes | |
float | cos_angle_tolerance_ |
float | max_edge_length_squared_ |
max (squared) length of edge | |
bool | store_shadowed_faces_ |
Whether or not shadowed faces are stored, e.g., for exploration. | |
int | triangle_pixel_size_ |
size of triangle endges (in pixels) | |
TriangulationType | triangulation_type_ |
Type of meshin scheme (quads vs. triangles, left cut vs. right cut ... |
Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular mesh.
Definition at line 58 of file organized_fast_mesh.h.
typedef pcl::PointCloud<PointInT>::Ptr pcl::OrganizedFastMesh< PointInT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointInT >.
Definition at line 64 of file organized_fast_mesh.h.
typedef std::vector<pcl::Vertices> pcl::OrganizedFastMesh< PointInT >::Polygons |
Definition at line 66 of file organized_fast_mesh.h.
enum pcl::OrganizedFastMesh::TriangulationType |
Definition at line 68 of file organized_fast_mesh.h.
pcl::OrganizedFastMesh< PointInT >::OrganizedFastMesh | ( | ) | [inline] |
Constructor. Triangulation type defaults to QUAD_MESH.
Definition at line 77 of file organized_fast_mesh.h.
pcl::OrganizedFastMesh< PointInT >::~OrganizedFastMesh | ( | ) | [inline] |
Destructor.
Definition at line 88 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::addQuad | ( | int | a, |
int | b, | ||
int | c, | ||
int | d, | ||
int | idx, | ||
std::vector< pcl::Vertices > & | polygons | ||
) | [inline, protected] |
Add a new quad to the current polygon mesh.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
[in] | d | index of the fourth vertex |
[in] | idx | the index in the set of polygon vertices (assumes idx is valid in polygons) |
[out] | polygons | the polygon mesh to be updated |
Definition at line 191 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::addTriangle | ( | int | a, |
int | b, | ||
int | c, | ||
int | idx, | ||
std::vector< pcl::Vertices > & | polygons | ||
) | [inline, protected] |
Add a new triangle to the current polygon mesh.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
[in] | idx | the index in the set of polygon vertices (assumes idx is valid in polygons) |
[out] | polygons | the polygon mesh to be updated |
Definition at line 173 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::isShadowed | ( | const PointInT & | point_a, |
const PointInT & | point_b | ||
) | [inline, protected] |
Check if a point is shadowed by another point.
[in] | point_a | the first point |
[in] | point_b | the second point |
Definition at line 224 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::isShadowedQuad | ( | const int & | a, |
const int & | b, | ||
const int & | c, | ||
const int & | d | ||
) | [inline, protected] |
Check if a triangle is shadowed.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
[in] | d | index of the fourth vertex |
Definition at line 289 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::isShadowedTriangle | ( | const int & | a, |
const int & | b, | ||
const int & | c | ||
) | [inline, protected] |
Check if a triangle is shadowed.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
Definition at line 258 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::isValidQuad | ( | const int & | a, |
const int & | b, | ||
const int & | c, | ||
const int & | d | ||
) | [inline, protected] |
Check if a quad is valid.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
[in] | d | index of the fourth vertex |
Definition at line 273 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::isValidTriangle | ( | const int & | a, |
const int & | b, | ||
const int & | c | ||
) | [inline, protected] |
Check if a triangle is valid.
[in] | a | index of the first vertex |
[in] | b | index of the second vertex |
[in] | c | index of the third vertex |
Definition at line 244 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::makeAdaptiveCutMesh | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected] |
Create an adaptive cut mesh.
[out] | polygons | the resultant mesh |
Definition at line 209 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::makeLeftCutMesh | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected] |
Create a left cut mesh.
[out] | polygons | the resultant mesh |
Definition at line 168 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::makeQuadMesh | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected] |
Create a quad mesh.
[out] | polygons | the resultant mesh |
Definition at line 90 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::makeRightCutMesh | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected] |
Create a right cut mesh.
[out] | polygons | the resultant mesh |
Definition at line 127 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::performReconstruction | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected, virtual] |
Create the surface.
[out] | polygons | the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. |
Implements pcl::MeshConstruction< PointInT >.
Definition at line 69 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [protected, virtual] |
Create the surface.
Simply uses image indices to create an initial polygonal mesh for organized point clouds. indices_ are ignored!
[out] | output | the resultant polygonal mesh |
Implements pcl::MeshConstruction< PointInT >.
Definition at line 48 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::reconstructPolygons | ( | std::vector< pcl::Vertices > & | polygons | ) | [protected] |
Perform the actual polygonal reconstruction.
[out] | polygons | the resultant polygons |
Definition at line 76 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::resetPointData | ( | const int & | point_index, |
pcl::PolygonMesh & | mesh, | ||
const float & | value = 0.0f , |
||
int | field_x_idx = 0 , |
||
int | field_y_idx = 1 , |
||
int | field_z_idx = 2 |
||
) | [inline, protected] |
Set (all) coordinates of a particular point to the specified value.
[in] | point_index | index of point |
[out] | mesh | to modify |
[in] | value | value to use when re-setting |
[in] | field_x_idx | the X coordinate of the point |
[in] | field_y_idx | the Y coordinate of the point |
[in] | field_z_idx | the Z coordinate of the point |
Definition at line 210 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setMaxEdgeLength | ( | float | max_edge_length | ) | [inline] |
Set a maximum edge length. TODO: Implement!
[in] | max_edge_length | the maximum edge length |
Definition at line 94 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSize | ( | int | triangle_size | ) | [inline] |
Set the edge length (in pixels) used for constructing the fixed mesh.
[in] | triangle_size | edge length in pixels (Default: 1 = neighboring pixels are connected) |
Definition at line 104 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setTriangulationType | ( | TriangulationType | type | ) | [inline] |
Set the triangulation type (see TriangulationType)
[in] | type | quad mesh, triangle mesh with fixed left, right cut, or adaptive cut (splits a quad wrt. the depth (z) of the points) |
Definition at line 114 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::storeShadowedFaces | ( | bool | enable | ) | [inline] |
Store shadowed faces or not.
[in] | enable | set to true to store shadowed faces |
Definition at line 123 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::cos_angle_tolerance_ [protected] |
Definition at line 141 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_squared_ [protected] |
max (squared) length of edge
Definition at line 130 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::store_shadowed_faces_ [protected] |
Whether or not shadowed faces are stored, e.g., for exploration.
Definition at line 139 of file organized_fast_mesh.h.
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_ [protected] |
size of triangle endges (in pixels)
Definition at line 133 of file organized_fast_mesh.h.
TriangulationType pcl::OrganizedFastMesh< PointInT >::triangulation_type_ [protected] |
Type of meshin scheme (quads vs. triangles, left cut vs. right cut ...
Definition at line 136 of file organized_fast_mesh.h.