Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular (or quad) mesh. More...
#include <organized_fast_mesh.h>
Public Types | |
typedef boost::shared_ptr < const OrganizedFastMesh < PointInT > > | ConstPtr |
typedef pcl::PointCloud < PointInT >::Ptr | PointCloudPtr |
typedef std::vector < pcl::Vertices > | Polygons |
typedef boost::shared_ptr < OrganizedFastMesh< PointInT > > | Ptr |
enum | TriangulationType { TRIANGLE_RIGHT_CUT, TRIANGLE_LEFT_CUT, TRIANGLE_ADAPTIVE_CUT, QUAD_MESH } |
Public Member Functions | |
const Eigen::Vector3f & | getViewpoint () const |
Get the viewpoint from where the input point cloud has been acquired. | |
OrganizedFastMesh () | |
Constructor. Triangulation type defaults to QUAD_MESH. | |
void | setAngleTolerance (float angle_tolerance) |
Set the angle tolerance used for checking whether or not an edge is occluded. Standard values are 5deg to 15deg (input in rad!). Set a value smaller than zero to disable the check for shadowed edges. | |
void | setDistanceTolerance (float distance_tolerance, bool depth_dependent=false) |
void | setMaxEdgeLength (float a, float b=0.0f, float c=0.0f) |
Set a maximum edge length. Using not only the scalar a, but also b and c, allows for using a distance threshold in the form of: threshold(x) = c*x*x + b*x + a. | |
void | setTrianglePixelSize (int triangle_size) |
Set the edge length (in pixels) used for constructing the fixed mesh. | |
void | setTrianglePixelSizeColumns (int triangle_size) |
Set the edge length (in pixels) used for iterating over columns when constructing the fixed mesh. | |
void | setTrianglePixelSizeRows (int triangle_size) |
Set the edge length (in pixels) used for iterating over rows when constructing the fixed mesh. | |
void | setTriangulationType (TriangulationType type) |
Set the triangulation type (see TriangulationType) | |
void | setViewpoint (const Eigen::Vector3f &viewpoint) |
Set the viewpoint from where the input point cloud has been acquired. | |
void | storeShadowedFaces (bool enable) |
Store shadowed faces or not. | |
void | unsetMaxEdgeLength () |
void | useDepthAsDistance (bool enable) |
Use the points' depths (z-coordinates) instead of measured distances (points' distances to the viewpoint). | |
virtual | ~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_ |
(Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed. | |
bool | distance_dependent_ |
flag whether or not distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not. | |
float | distance_tolerance_ |
distance tolerance for filtering out shadowed/occluded edges | |
float | max_edge_length_a_ |
max length of edge, scalar component | |
float | max_edge_length_b_ |
max length of edge, scalar component | |
float | max_edge_length_c_ |
max length of edge, scalar component | |
bool | max_edge_length_dist_dependent_ |
flag whether or not max edge length is distance dependent. | |
bool | max_edge_length_set_ |
flag whether or not edges are limited in length | |
bool | store_shadowed_faces_ |
Whether or not shadowed faces are stored, e.g., for exploration. | |
int | triangle_pixel_size_columns_ |
size of triangle edges (in pixels) for iterating over columns | |
int | triangle_pixel_size_rows_ |
size of triangle edges (in pixels) for iterating over rows. | |
TriangulationType | triangulation_type_ |
Type of meshing scheme (quads vs. triangles, left cut vs. right cut ... | |
bool | use_depth_as_distance_ |
flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint). This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up. | |
Eigen::Vector3f | viewpoint_ |
Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data). |
Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular (or quad) mesh.
Definition at line 65 of file organized_fast_mesh.h.
typedef boost::shared_ptr<const OrganizedFastMesh<PointInT> > pcl::OrganizedFastMesh< PointInT >::ConstPtr |
Definition at line 69 of file organized_fast_mesh.h.
typedef pcl::PointCloud<PointInT>::Ptr pcl::OrganizedFastMesh< PointInT >::PointCloudPtr |
Definition at line 74 of file organized_fast_mesh.h.
typedef std::vector<pcl::Vertices> pcl::OrganizedFastMesh< PointInT >::Polygons |
Definition at line 76 of file organized_fast_mesh.h.
typedef boost::shared_ptr<OrganizedFastMesh<PointInT> > pcl::OrganizedFastMesh< PointInT >::Ptr |
Definition at line 68 of file organized_fast_mesh.h.
enum pcl::OrganizedFastMesh::TriangulationType |
Definition at line 78 of file organized_fast_mesh.h.
pcl::OrganizedFastMesh< PointInT >::OrganizedFastMesh | ( | ) | [inline] |
Constructor. Triangulation type defaults to QUAD_MESH.
Definition at line 87 of file organized_fast_mesh.h.
virtual pcl::OrganizedFastMesh< PointInT >::~OrganizedFastMesh | ( | ) | [inline, virtual] |
Destructor.
Definition at line 107 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 321 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 303 of file organized_fast_mesh.h.
const Eigen::Vector3f& pcl::OrganizedFastMesh< PointInT >::getViewpoint | ( | ) | const [inline] |
Get the viewpoint from where the input point cloud has been acquired.
Definition at line 184 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 354 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 453 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 422 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 437 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 408 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 210 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 169 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 91 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 128 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. |
Definition at line 70 of file organized_fast_mesh.hpp.
void pcl::OrganizedFastMesh< PointInT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [protected] |
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 |
Definition at line 49 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 77 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 340 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setAngleTolerance | ( | float | angle_tolerance | ) | [inline] |
Set the angle tolerance used for checking whether or not an edge is occluded. Standard values are 5deg to 15deg (input in rad!). Set a value smaller than zero to disable the check for shadowed edges.
[in] | angle_tolerance | Angle tolerance (in rad). Set a value <0 to disable. |
Definition at line 204 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setDistanceTolerance | ( | float | distance_tolerance, |
bool | depth_dependent = false |
||
) | [inline] |
Definition at line 213 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setMaxEdgeLength | ( | float | a, |
float | b = 0.0f , |
||
float | c = 0.0f |
||
) | [inline] |
Set a maximum edge length. Using not only the scalar a, but also b and c, allows for using a distance threshold in the form of: threshold(x) = c*x*x + b*x + a.
[in] | a | scalar coefficient of the (distance-dependent polynom) threshold |
[in] | b | linear coefficient of the (distance-dependent polynom) threshold |
[in] | c | quadratic coefficient of the (distance-dependent polynom) threshold |
Definition at line 117 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 139 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSizeColumns | ( | int | triangle_size | ) | [inline] |
Set the edge length (in pixels) used for iterating over columns when constructing the fixed mesh.
[in] | triangle_size | edge length in pixels (Default: 1 = neighboring pixels are connected) |
Definition at line 160 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSizeRows | ( | int | triangle_size | ) | [inline] |
Set the edge length (in pixels) used for iterating over rows when constructing the fixed mesh.
[in] | triangle_size | edge length in pixels (Default: 1 = neighboring pixels are connected) |
Definition at line 150 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 w.r.t. the depth (z) of the points) |
Definition at line 170 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::setViewpoint | ( | const Eigen::Vector3f & | viewpoint | ) | [inline] |
Set the viewpoint from where the input point cloud has been acquired.
[in] | viewpoint | Vector containing the viewpoint coordinates (in the coordinate system of the data) |
Definition at line 178 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 193 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::unsetMaxEdgeLength | ( | ) | [inline] |
Definition at line 129 of file organized_fast_mesh.h.
void pcl::OrganizedFastMesh< PointInT >::useDepthAsDistance | ( | bool | enable | ) | [inline] |
Use the points' depths (z-coordinates) instead of measured distances (points' distances to the viewpoint).
[in] | enable | Set to true skips comptations and further speeds up computation by using depth instead of computing distance. false to disable. |
Definition at line 226 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::cos_angle_tolerance_ [protected] |
(Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed.
Definition at line 260 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::distance_dependent_ [protected] |
flag whether or not distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not.
Definition at line 266 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::distance_tolerance_ [protected] |
distance tolerance for filtering out shadowed/occluded edges
Definition at line 263 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_a_ [protected] |
max length of edge, scalar component
Definition at line 233 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_b_ [protected] |
max length of edge, scalar component
Definition at line 235 of file organized_fast_mesh.h.
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_c_ [protected] |
max length of edge, scalar component
Definition at line 237 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::max_edge_length_dist_dependent_ [protected] |
flag whether or not max edge length is distance dependent.
Definition at line 242 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::max_edge_length_set_ [protected] |
flag whether or not edges are limited in length
Definition at line 239 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 257 of file organized_fast_mesh.h.
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_columns_ [protected] |
size of triangle edges (in pixels) for iterating over columns
Definition at line 248 of file organized_fast_mesh.h.
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_rows_ [protected] |
size of triangle edges (in pixels) for iterating over rows.
Definition at line 245 of file organized_fast_mesh.h.
TriangulationType pcl::OrganizedFastMesh< PointInT >::triangulation_type_ [protected] |
Type of meshing scheme (quads vs. triangles, left cut vs. right cut ...
Definition at line 251 of file organized_fast_mesh.h.
bool pcl::OrganizedFastMesh< PointInT >::use_depth_as_distance_ [protected] |
flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint). This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up.
Definition at line 270 of file organized_fast_mesh.h.
Eigen::Vector3f pcl::OrganizedFastMesh< PointInT >::viewpoint_ [protected] |
Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data).
Definition at line 254 of file organized_fast_mesh.h.