The marching cubes surface reconstruction algorithm. This is an abstract class that takes a grid and extracts the isosurface as a mesh, based on the original marching cubes paper: More...
#include <marching_cubes.h>
Public Types | |
typedef pcl::KdTree< PointNT > | KdTree |
typedef pcl::KdTree< PointNT >::Ptr | KdTreePtr |
typedef pcl::PointCloud < PointNT >::Ptr | PointCloudPtr |
Public Member Functions | |
void | getGridResolution (int &res_x, int &res_y, int &res_z) |
Method to get the marching cubes grid resolution. | |
float | getIsoLevel () |
Method that returns the iso level of the surface to be extracted. | |
float | getPercentageExtendGrid () |
Method that gets the parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits, as a percentage of the bounding box. | |
MarchingCubes () | |
Constructor. | |
void | setGridResolution (int res_x, int res_y, int res_z) |
Method that sets the marching cubes grid resolution. | |
void | setIsoLevel (float iso_level) |
Method that sets the iso level of the surface to be extracted. | |
void | setPercentageExtendGrid (float percentage) |
Method that sets the parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits. Does not affect the resolution of the grid, it just changes the voxel size accordingly. | |
~MarchingCubes () | |
Destructor. | |
Protected Member Functions | |
void | createSurface (std::vector< float > &leaf_node, Eigen::Vector3i &index_3d, pcl::PointCloud< PointNT > &cloud) |
Calculate out the corresponding polygons in the leaf node. | |
void | getBoundingBox () |
Get the bounding box for the input data points. | |
std::string | getClassName () const |
Class get name method. | |
float | getGridValue (Eigen::Vector3i pos) |
Method that returns the scalar value at the given grid position. | |
void | getNeighborList1D (std::vector< float > &leaf, Eigen::Vector3i &index3d) |
Method that returns the scalar values of the neighbors of a given 3D position in the grid. | |
void | interpolateEdge (Eigen::Vector3f &p1, Eigen::Vector3f &p2, float val_p1, float val_p2, Eigen::Vector3f &output) |
Interpolate along the voxel edge. | |
void | performReconstruction (pcl::PolygonMesh &output) |
Extract the surface. | |
void | performReconstruction (pcl::PointCloud< PointNT > &points, std::vector< pcl::Vertices > &polygons) |
Extract the surface. | |
virtual void | voxelizeData ()=0 |
Convert the point cloud into voxel data. | |
Protected Attributes | |
std::vector< float > | grid_ |
The data structure storing the 3D grid. | |
float | iso_level_ |
The iso level to be extracted. | |
Eigen::Vector4f | max_p_ |
Eigen::Vector4f | min_p_ |
Min and max data points. | |
float | percentage_extend_grid_ |
Parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits, as a percentage of the bounding box. | |
int | res_x_ |
The grid resolution. | |
int | res_y_ |
int | res_z_ |
The marching cubes surface reconstruction algorithm. This is an abstract class that takes a grid and extracts the isosurface as a mesh, based on the original marching cubes paper:
Lorensen W.E., Cline H.E., "Marching cubes: A high resolution 3d surface construction algorithm", SIGGRAPH '87
Definition at line 363 of file marching_cubes.h.
typedef pcl::KdTree<PointNT> pcl::MarchingCubes< PointNT >::KdTree |
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
Reimplemented in pcl::MarchingCubesRBF< PointNT >, and pcl::MarchingCubesHoppe< PointNT >.
Definition at line 371 of file marching_cubes.h.
typedef pcl::KdTree<PointNT>::Ptr pcl::MarchingCubes< PointNT >::KdTreePtr |
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
Reimplemented in pcl::MarchingCubesRBF< PointNT >, and pcl::MarchingCubesHoppe< PointNT >.
Definition at line 372 of file marching_cubes.h.
typedef pcl::PointCloud<PointNT>::Ptr pcl::MarchingCubes< PointNT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointNT >.
Reimplemented in pcl::MarchingCubesRBF< PointNT >, and pcl::MarchingCubesHoppe< PointNT >.
Definition at line 369 of file marching_cubes.h.
pcl::MarchingCubes< PointNT >::MarchingCubes | ( | ) |
Constructor.
Definition at line 47 of file marching_cubes.hpp.
pcl::MarchingCubes< PointNT >::~MarchingCubes | ( | ) |
Destructor.
Definition at line 54 of file marching_cubes.hpp.
void pcl::MarchingCubes< PointNT >::createSurface | ( | std::vector< float > & | leaf_node, |
Eigen::Vector3i & | index_3d, | ||
pcl::PointCloud< PointNT > & | cloud | ||
) | [protected] |
Calculate out the corresponding polygons in the leaf node.
leaf_node | the leaf node to be checked |
index_3d | the 3d index of the leaf node to be checked |
cloud | point cloud to store the vertices of the polygon |
Definition at line 99 of file marching_cubes.hpp.
void pcl::MarchingCubes< PointNT >::getBoundingBox | ( | ) | [protected] |
Get the bounding box for the input data points.
Definition at line 60 of file marching_cubes.hpp.
std::string pcl::MarchingCubes< PointNT >::getClassName | ( | ) | const [inline, protected, virtual] |
Class get name method.
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
Definition at line 492 of file marching_cubes.h.
void pcl::MarchingCubes< PointNT >::getGridResolution | ( | int & | res_x, |
int & | res_y, | ||
int & | res_z | ||
) | [inline] |
Method to get the marching cubes grid resolution.
[in] | res_x | the resolution of the grid along the x-axis |
[in] | res_y | the resolution of the grid along the y-axis |
[in] | res_z | the resolution of the grid along the z-axis |
Definition at line 410 of file marching_cubes.h.
float pcl::MarchingCubes< PointNT >::getGridValue | ( | Eigen::Vector3i | pos | ) | [protected] |
Method that returns the scalar value at the given grid position.
[in] | pos | The 3D position in the grid |
TODO what to return?
Definition at line 208 of file marching_cubes.hpp.
float pcl::MarchingCubes< PointNT >::getIsoLevel | ( | ) | [inline] |
Method that returns the iso level of the surface to be extracted.
Definition at line 391 of file marching_cubes.h.
void pcl::MarchingCubes< PointNT >::getNeighborList1D | ( | std::vector< float > & | leaf, |
Eigen::Vector3i & | index3d | ||
) | [protected] |
Method that returns the scalar values of the neighbors of a given 3D position in the grid.
[in] | index3d | the point in the grid |
[out] | leaf | the set of values |
Definition at line 190 of file marching_cubes.hpp.
float pcl::MarchingCubes< PointNT >::getPercentageExtendGrid | ( | ) | [inline] |
Method that gets the parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits, as a percentage of the bounding box.
Definition at line 427 of file marching_cubes.h.
void pcl::MarchingCubes< PointNT >::interpolateEdge | ( | Eigen::Vector3f & | p1, |
Eigen::Vector3f & | p2, | ||
float | val_p1, | ||
float | val_p2, | ||
Eigen::Vector3f & | output | ||
) | [protected] |
Interpolate along the voxel edge.
[in] | p1 | The first point on the edge |
[in] | p2 | The second point on the edge |
[in] | val_p1 | The scalar value at p1 |
[in] | val_p2 | The scalar value at p2 |
[out] | output | The interpolated point along the edge |
Definition at line 86 of file marching_cubes.hpp.
void pcl::MarchingCubes< PointNT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [protected, virtual] |
Extract the surface.
[out] | output | the resultant polygonal mesh |
Implements pcl::SurfaceReconstruction< PointNT >.
Definition at line 224 of file marching_cubes.hpp.
void pcl::MarchingCubes< PointNT >::performReconstruction | ( | pcl::PointCloud< PointNT > & | points, |
std::vector< pcl::Vertices > & | polygons | ||
) | [protected, virtual] |
Extract the surface.
[out] | points | the points of the extracted mesh |
[out] | polygons | the connectivity between the point of the extracted mesh. |
Implements pcl::SurfaceReconstruction< PointNT >.
Definition at line 278 of file marching_cubes.hpp.
void pcl::MarchingCubes< PointNT >::setGridResolution | ( | int | res_x, |
int | res_y, | ||
int | res_z | ||
) | [inline] |
Method that sets the marching cubes grid resolution.
[in] | res_x | the resolution of the grid along the x-axis |
[in] | res_y | the resolution of the grid along the y-axis |
[in] | res_z | the resolution of the grid along the z-axis |
Definition at line 400 of file marching_cubes.h.
void pcl::MarchingCubes< PointNT >::setIsoLevel | ( | float | iso_level | ) | [inline] |
Method that sets the iso level of the surface to be extracted.
[in] | iso_level | the iso level. |
Definition at line 386 of file marching_cubes.h.
void pcl::MarchingCubes< PointNT >::setPercentageExtendGrid | ( | float | percentage | ) | [inline] |
Method that sets the parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits. Does not affect the resolution of the grid, it just changes the voxel size accordingly.
[in] | percentage | the percentage of the bounding box that should be left empty between the bounding box and the grid limits. |
Definition at line 420 of file marching_cubes.h.
virtual void pcl::MarchingCubes< PointNT >::voxelizeData | ( | ) | [protected, pure virtual] |
Convert the point cloud into voxel data.
Implemented in pcl::MarchingCubesRBF< PointNT >, and pcl::MarchingCubesHoppe< PointNT >.
std::vector<float> pcl::MarchingCubes< PointNT >::grid_ [protected] |
The data structure storing the 3D grid.
Definition at line 432 of file marching_cubes.h.
float pcl::MarchingCubes< PointNT >::iso_level_ [protected] |
The iso level to be extracted.
Definition at line 445 of file marching_cubes.h.
Eigen::Vector4f pcl::MarchingCubes< PointNT >::max_p_ [protected] |
Definition at line 442 of file marching_cubes.h.
Eigen::Vector4f pcl::MarchingCubes< PointNT >::min_p_ [protected] |
Min and max data points.
Definition at line 442 of file marching_cubes.h.
float pcl::MarchingCubes< PointNT >::percentage_extend_grid_ [protected] |
Parameter that defines how much free space should be left inside the grid between the bounding box of the point cloud and the grid limits, as a percentage of the bounding box.
Definition at line 439 of file marching_cubes.h.
int pcl::MarchingCubes< PointNT >::res_x_ [protected] |
The grid resolution.
Definition at line 435 of file marching_cubes.h.
int pcl::MarchingCubes< PointNT >::res_y_ [protected] |
Definition at line 435 of file marching_cubes.h.
int pcl::MarchingCubes< PointNT >::res_z_ [protected] |
Definition at line 435 of file marching_cubes.h.