Point Cloud Library (PCL)  1.14.0-dev
standalone_marching_cubes.h
1  /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #pragma once
39 
40 //General includes and I/O
41 
42 #include <iostream>
43 #include <pcl/io/pcd_io.h>
44 #include <pcl/io/ply_io.h>
45 #include <pcl/io/vtk_io.h>
46 #include <pcl/point_types.h>
47 #include <cstdio>
48 #include <cstdarg>
49 #include <pcl/pcl_macros.h>
50 
51 //Marching cubes includes
52 #include <pcl/gpu/kinfu_large_scale/marching_cubes.h>
53 #include <pcl/PolygonMesh.h>
54 
55 #include <pcl/gpu/containers/device_array.h>
56 
57 //TSDF volume includes
58 #include <pcl/gpu/kinfu_large_scale/tsdf_volume.h>
59 
60 //Eigen Geometry and Transforms
61 #include <pcl/common/transforms.h>
62 #include <Eigen/Geometry>
63 //#include <boost/graph/buffer_concepts.hpp>
64 
65 namespace pcl
66 {
67  namespace gpu
68  {
69  namespace kinfuLS
70  {
71  /** \brief The Standalone Marching Cubes Class provides encapsulated functionality for the Marching Cubes implementation originally by Anatoly Baksheev.
72  * \author Raphael Favier
73  * \author Francisco Heredia
74  */
75 
76  template <typename PointT>
78  {
79  public:
81  using PointCloudPtr = typename PointCloud::Ptr;
83 
84  /** \brief Constructor
85  */
86  StandaloneMarchingCubes (int voxels_x = 512, int voxels_y = 512, int voxels_z = 512, float volume_size = 3.0f);
87 
88 
89  /** \brief Run marching cubes in a TSDF cloud and returns a PolygonMesh. Input X,Y,Z coordinates must be in indices of the TSDF volume grid, output is in meters.
90  * \param[in] cloud TSDF cloud with indices between [0 ... VOXELS_X][0 ... VOXELS_Y][0 ... VOXELS_Z]. Intensity value corresponds to the TSDF value in that coordinate.
91  * \return pointer to a PolygonMesh in meters generated by marching cubes.
92  */
93  MeshPtr
94  getMeshFromTSDFCloud (const PointCloud &cloud);
95 
96  /** \brief Runs marching cubes on every pointcloud in the vector. Returns a vector containing the PolygonMeshes.
97  * \param[in] tsdf_clouds Vector of TSDF Clouds
98  * \param[in] tsdf_offsets Vector of the offsets for every pointcloud in TsdfClouds. This offset (in indices) indicates the position of the cloud with respect to the absolute origin of the world model
99  */
100  void
101  getMeshesFromTSDFVector (const std::vector<PointCloudPtr> &tsdf_clouds, const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > &tsdf_offsets);
102 
103  /** \brief Returns the associated Tsdf Volume buffer in GPU
104  * \return pointer to the Tsdf Volume buffer in GPU
105  */
107  tsdfVolumeGPU ();
108 
109  /** \brief Returns the associated Tsdf Volume buffer in CPU
110  * \return the Tsdf Volume buffer in CPU returned returned by reference
111  */
112  std::vector<int>&
113  tsdfVolumeCPU ();
114 
115  protected:
116 
117  /** \brief Loads a TSDF Cloud to the TSDF Volume in GPU
118  * \param[in] cloud TSDF cloud that will be loaded. X,Y,Z of the cloud will only be loaded if their range is between [0 ... VOXELS_X][0 ... VOXELS_Y][0 ... VOXELS_Z]
119  */
120  void
121  loadTsdfCloudToGPU (const PointCloud &cloud);
122 
123  /** \brief Read the data in the point cloud. Performs a conversion to a suitable format for the TSDF Volume. Loads the converted data to the output vector.
124  * \param[in] cloud point cloud to be converted
125  * \param[out] output the vector of converted values, ready to be loaded to the GPU.
126  */
127  void
128  convertTsdfVectors (const PointCloud &cloud, std::vector<int> &output);
129 
130  /** \brief Converts the triangles buffer device to a PolygonMesh.
131  * \param[in] triangles the triangles buffer containing the points of the mesh
132  * \return pointer to the PolygonMesh egnerated by marchign cubes
133  */
134  MeshPtr
136 
137  /** \brief Runs marching cubes on the data that is contained in the TSDF Volume in GPU.
138  * \return param[return] pointer to a PolygonMesh in meters generated by marching cubes.
139  */
140  MeshPtr
141  runMarchingCubes ();
142 
143  private:
144 
145  /** The TSDF volume in GPU*/
146  TsdfVolume::Ptr tsdf_volume_gpu_;
147 
148  /** The TSDF volume in CPU */
149  std::vector<int> tsdf_volume_cpu_;
150 
151  /** Number of voxels in the grid for each axis */
152  int voxels_x_;
153  int voxels_y_;
154  int voxels_z_;
155 
156  /** Tsdf volume size in meters. Should match the ones in internal.h */
157  float volume_size_;
158 
159  /** Mesh counter used to name the output meshes */
160  int mesh_counter_;
161 
162  };
163  }
164  }
165 }
166 
167 #define PCL_INSTANTIATE_StandaloneMarchingCubes(PointT) template class PCL_EXPORTS pcl::gpu::kinfuLS::StandaloneMarchingCubes<PointT>;
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
The Standalone Marching Cubes Class provides encapsulated functionality for the Marching Cubes implem...
StandaloneMarchingCubes(int voxels_x=512, int voxels_y=512, int voxels_z=512, float volume_size=3.0f)
Constructor
MeshPtr getMeshFromTSDFCloud(const PointCloud &cloud)
Run marching cubes in a TSDF cloud and returns a PolygonMesh.
MeshPtr convertTrianglesToMesh(const pcl::gpu::DeviceArray< pcl::PointXYZ > &triangles)
Converts the triangles buffer device to a PolygonMesh.
void getMeshesFromTSDFVector(const std::vector< PointCloudPtr > &tsdf_clouds, const std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &tsdf_offsets)
Runs marching cubes on every pointcloud in the vector.
void convertTsdfVectors(const PointCloud &cloud, std::vector< int > &output)
Read the data in the point cloud.
std::vector< int > & tsdfVolumeCPU()
Returns the associated Tsdf Volume buffer in CPU.
void loadTsdfCloudToGPU(const PointCloud &cloud)
Loads a TSDF Cloud to the TSDF Volume in GPU.
MeshPtr runMarchingCubes()
Runs marching cubes on the data that is contained in the TSDF Volume in GPU.
TsdfVolume::Ptr tsdfVolumeGPU()
Returns the associated Tsdf Volume buffer in GPU.
shared_ptr< TsdfVolume > Ptr
Definition: tsdf_volume.h:65
Defines all the PCL implemented PointT point type structures.
Defines all the PCL and non-PCL macros used.
shared_ptr< ::pcl::PolygonMesh > Ptr
Definition: PolygonMesh.h:96