39 #ifndef MeshStage_HPP__ 40 #define MeshStage_HPP__ 45 #include <boost/any.hpp> 46 #include <lvr/reconstruction/FastReconstruction.hpp> 47 #include <lvr/reconstruction/TSDFGrid.hpp> 48 #include <lvr/reconstruction/PointsetSurface.hpp> 49 #include <lvr/reconstruction/FastKinFuBox.hpp> 50 #include <lvr/io/PointBuffer.hpp> 51 #include <lvr/io/DataStruct.hpp> 52 #include <lvr/geometry/HalfEdgeVertex.hpp> 53 #include <lvr/geometry/HalfEdgeKinFuMesh.hpp> 54 #include <lvr/geometry/BoundingBox.hpp> 55 #include <lvr/geometry/Matrix4.hpp> 58 #include <opencv2/flann/flann.hpp> 66 typedef ColorVertex<float, unsigned char>
cVertex;
67 typedef FastKinFuBox<ColorVertex<float, unsigned char>, lvr::Normal<float> >
cFastBox;
68 typedef TsdfGrid<cVertex, cFastBox, kfusion::Point>
TGrid;
70 typedef HalfEdgeKinFuMesh<cVertex, lvr::Normal<float> >
HMesh;
80 virtual void firstStep();
82 virtual void lastStep();
FastKinFuBox< ColorVertex< float, unsigned char >, lvr::Normal< float > > cFastBox
HalfEdgeKinFuMesh< cVertex, lvr::Normal< float > > HMesh
Eigen::Matrix4f Matrix4f
Eigen 4x4 matrix, single precision.
const kaboom::Options * options
double camera_target_distance_
HalfEdgeKinFuMesh< cVertex, lvr::Normal< float > > HMesh
A class to parse the program options for the reconstruction executable.
lvr::Matrix4f global_correction_
ColorVertex< float, unsigned char > cVertex
TsdfGrid< cVertex, cFastBox, kfusion::Point > TGrid
FastKinFuBox< ColorVertex< float, unsigned char >, lvr::Normal< float > > cFastBox
FastReconstruction< ColorVertex< float, unsigned char >, lvr::Normal< float >, cFastBox > cFastReconstruction
queue< MeshPtr > last_mesh_queue_